Skip to content

Commit

Permalink
Merge pull request #300 from ros-drivers/263-check-if-specified-pixel…
Browse files Browse the repository at this point in the history
…-format-is-supported

263 check if specified pixel format is supported
  • Loading branch information
flynneva authored Dec 5, 2023
2 parents c052be0 + d9d12d4 commit cd69723
Show file tree
Hide file tree
Showing 12 changed files with 194 additions and 96 deletions.
4 changes: 2 additions & 2 deletions config/params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
framerate: 15.0
io_method: "mmap"
frame_id: "camera2"
pixel_format: "mjpeg2rgb" # see usb_cam/supported_formats for list of supported formats
av_device_format: "YUV422P"
pixel_format: "mjpeg2rgb"
av_device_format: "YUV422P"
image_width: 640
image_height: 480
camera_name: "test_camera2"
Expand Down
33 changes: 33 additions & 0 deletions include/usb_cam/formats/av_pixel_format_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -960,6 +960,7 @@ inline AVPixelFormat get_av_pixel_format_from_string(const std::string & str)
return STR_2_AVPIXFMT.find(fullFmtStr)->second;
}


/// @brief Get ROS PixelFormat from AVPixelFormat.
/// @param avPixelFormat AVPixelFormat
/// @return String specifying the ROS pixel format.
Expand Down Expand Up @@ -1032,6 +1033,17 @@ inline std::string get_ros_pixel_format_from_av_format(const AVPixelFormat & avP
return ros_format;
}


/// @brief Overload to support av pixel formats being passed as strings
/// @param avPixelFormat AvPixelFormat as string
/// @return String specifying the ROS pixel format.
inline std::string get_ros_pixel_format_from_av_format(const std::string avPixelFormatStr)
{
auto fmt = get_av_pixel_format_from_string(avPixelFormatStr);
return get_ros_pixel_format_from_av_format(fmt);
}


/// @brief Get the number of channels from AVPixelFormat.
/// @param avPixelFormat AVPixelFormat
/// @return Number of channels as uint8
Expand Down Expand Up @@ -1074,6 +1086,17 @@ inline uint8_t get_channels_from_av_format(const AVPixelFormat & avPixelFormat)
return channels;
}


/// @brief Overload of function below to support av pixel formats as strings
/// @param avPixelFormatStr AvPixelFormat as string
/// @return Number of channels as uint8_t
inline uint8_t get_channels_from_av_format(const std::string & avPixelFormatStr)
{
auto fmt = get_av_pixel_format_from_string(avPixelFormatStr);
return get_channels_from_av_format(fmt);
}


/// @brief Get the pixel bit depth from AVPixelFormat.
/// @param avPixelFormat AVPixelFormat
/// @return Bit depth as uint8
Expand Down Expand Up @@ -1106,6 +1129,16 @@ inline uint8_t get_bit_depth_from_av_format(const AVPixelFormat & avPixelFormat)
return bit_depth;
}


/// @brief Overload of function below to support passing av pixel formats as strings
/// @param avPixelFormatStr AVPixelFormat as string
/// @return Bit depth as uint8
inline uint8_t get_bit_depth_from_av_format(const std::string & avPixelFormatStr)
{
auto fmt = get_av_pixel_format_from_string(avPixelFormatStr);
return get_bit_depth_from_av_format(fmt);
}

} // namespace formats
} // namespace usb_cam

Expand Down
6 changes: 3 additions & 3 deletions include/usb_cam/formats/m420.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,16 +46,16 @@ namespace formats
class M4202RGB : public pixel_format_base
{
public:
M4202RGB(const int & width, const int & height)
explicit M4202RGB(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"m4202rgb",
V4L2_PIX_FMT_M420,
usb_cam::constants::RGB8,
3,
8,
true),
m_width(width),
m_height(height)
m_width(args.width),
m_height(args.height)
{}

/// @brief Convert a YUV420 (aka M420) image to RGB8
Expand Down
31 changes: 15 additions & 16 deletions include/usb_cam/formats/mjpeg.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,22 +63,21 @@ namespace formats
class RAW_MJPEG : public pixel_format_base
{
public:
explicit RAW_MJPEG(const AVPixelFormat & avDeviceFormat)
explicit RAW_MJPEG(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"raw_mjpeg",
V4L2_PIX_FMT_MJPEG,
get_ros_pixel_format_from_av_format(avDeviceFormat),
get_channels_from_av_format(avDeviceFormat),
get_bit_depth_from_av_format(avDeviceFormat),
get_ros_pixel_format_from_av_format(args.av_device_format_str),
get_channels_from_av_format(args.av_device_format_str),
get_bit_depth_from_av_format(args.av_device_format_str),
false)
{
}
{}
};

class MJPEG2RGB : public pixel_format_base
{
public:
MJPEG2RGB(const int & width, const int & height, const AVPixelFormat & avDeviceFormat)
explicit MJPEG2RGB(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"mjpeg2rgb",
V4L2_PIX_FMT_MJPEG,
Expand All @@ -103,27 +102,27 @@ class MJPEG2RGB : public pixel_format_base

m_avcodec_context = avcodec_alloc_context3(m_avcodec);

m_avframe_device->width = width;
m_avframe_device->height = height;
m_avframe_device->width = args.width;
m_avframe_device->height = args.height;
m_avframe_device->format = AV_PIX_FMT_YUV422P;
m_avframe_device->format = avDeviceFormat;
m_avframe_device->format = formats::get_av_pixel_format_from_string(args.av_device_format_str);

m_avframe_rgb->width = width;
m_avframe_rgb->height = height;
m_avframe_rgb->width = args.width;
m_avframe_rgb->height = args.height;
m_avframe_rgb->format = AV_PIX_FMT_RGB24;

m_sws_context = sws_getContext(
width, height, (AVPixelFormat)m_avframe_device->format,
width, height, (AVPixelFormat)m_avframe_rgb->format, SWS_FAST_BILINEAR,
args.width, args.height, (AVPixelFormat)m_avframe_device->format,
args.width, args.height, (AVPixelFormat)m_avframe_rgb->format, SWS_FAST_BILINEAR,
NULL, NULL, NULL);

// Suppress warnings from ffmpeg libraries to avoid spamming the console
av_log_set_level(AV_LOG_FATAL);
av_log_set_flags(AV_LOG_SKIP_REPEATED);
// av_log_set_flags(AV_LOG_PRINT_LEVEL);

m_avcodec_context->width = width;
m_avcodec_context->height = height;
m_avcodec_context->width = args.width;
m_avcodec_context->height = args.height;
m_avcodec_context->pix_fmt = (AVPixelFormat)m_avframe_device->format;
m_avcodec_context->codec_type = AVMEDIA_TYPE_VIDEO;

Expand Down
16 changes: 10 additions & 6 deletions include/usb_cam/formats/mono.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,46 +44,50 @@ namespace formats
class MONO8 : public pixel_format_base
{
public:
MONO8()
explicit MONO8(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"mono8",
V4L2_PIX_FMT_GREY,
usb_cam::constants::MONO8,
1,
8,
false)
{}
{
(void)args;
}
};


class MONO16 : public pixel_format_base
{
public:
MONO16()
explicit MONO16(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"mono16",
V4L2_PIX_FMT_Y16,
usb_cam::constants::MONO16,
1,
16,
false)
{}
{
(void)args;
}
};


/// @brief Also known as MONO10 to MONO8
class Y102MONO8 : public pixel_format_base
{
public:
explicit Y102MONO8(const int & number_of_pixels)
explicit Y102MONO8(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"y102mono8",
V4L2_PIX_FMT_Y10,
usb_cam::constants::MONO8,
1,
8,
true),
m_number_of_pixels(number_of_pixels)
m_number_of_pixels(args.pixels)
{}

/// @brief Convert a Y10 (MONO10) image to MONO8
Expand Down
23 changes: 21 additions & 2 deletions include/usb_cam/formats/pixel_format_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,29 @@
#include "linux/videodev2.h"

#include "usb_cam/constants.hpp"

#include "usb_cam/conversions.hpp"

namespace usb_cam
{
namespace formats
{


/// @brief Helper structure to standardize all pixel_format_base
/// constructors, so that they all have the same argument type.
///
/// This should also be easily extendable in the future if we need to add additional
/// arguments for future pixel format(s) that are added.
typedef struct
{
std::string name = "";
int width = 640;
int height = 480;
size_t pixels = 640 * 480;
std::string av_device_format_str = "AV_PIX_FMT_YUV422P";
} format_arguments_t;


/// @brief Base pixel format class. Provide all necessary information for converting between
/// V4L2 and ROS formats. Meant to be overridden if conversion function is required.
class pixel_format_base
Expand All @@ -64,9 +79,13 @@ class pixel_format_base
inline std::string name() {return m_name;}

/// @brief Integer value of V4L2 capture pixel format
/// @return
/// @return uint32_t V4L2 capture pixel format
inline uint32_t v4l2() {return m_v4l2;}

/// @brief String value of V4L2 capture pixel format
/// @return std::string V4L2 capture pixel format
inline std::string v4l2_str() {return usb_cam::conversions::FCC2S(m_v4l2);}

/// @brief Name of output pixel (encoding) format to ROS
/// @return
inline std::string ros() {return m_ros;}
Expand Down
6 changes: 4 additions & 2 deletions include/usb_cam/formats/rgb.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,15 +44,17 @@ namespace formats
class RGB8 : public pixel_format_base
{
public:
RGB8()
explicit RGB8(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"rgb8",
V4L2_PIX_FMT_RGB332,
usb_cam::constants::RGB8,
3,
8,
false)
{}
{
(void)args;
}
};

} // namespace formats
Expand Down
10 changes: 6 additions & 4 deletions include/usb_cam/formats/uyvy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,30 +44,32 @@ namespace formats
class UYVY : public pixel_format_base
{
public:
UYVY()
explicit UYVY(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"uyvy",
V4L2_PIX_FMT_UYVY,
usb_cam::constants::YUV422,
2,
8,
false)
{}
{
(void)args;
}
};


class UYVY2RGB : public pixel_format_base
{
public:
explicit UYVY2RGB(const int & number_of_pixels)
explicit UYVY2RGB(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"uyvy2rgb",
V4L2_PIX_FMT_UYVY,
usb_cam::constants::RGB8,
3,
8,
true),
m_number_of_pixels(number_of_pixels)
m_number_of_pixels(args.pixels)
{}

/// @brief In this format each four bytes is two pixels.
Expand Down
10 changes: 6 additions & 4 deletions include/usb_cam/formats/yuyv.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,30 +44,32 @@ namespace formats
class YUYV : public pixel_format_base
{
public:
YUYV()
explicit YUYV(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"yuyv",
V4L2_PIX_FMT_YUYV,
usb_cam::constants::YUV422_YUY2,
2,
8,
false)
{}
{
(void)args;
}
};


class YUYV2RGB : public pixel_format_base
{
public:
explicit YUYV2RGB(const int & number_of_pixels)
explicit YUYV2RGB(const format_arguments_t & args = format_arguments_t())
: pixel_format_base(
"yuyv2rgb",
V4L2_PIX_FMT_YUYV,
usb_cam::constants::RGB8,
3,
8,
true),
m_number_of_pixels(number_of_pixels)
m_number_of_pixels(args.pixels)
{}

/// @brief In this format each four bytes is two pixels.
Expand Down
Loading

0 comments on commit cd69723

Please sign in to comment.