Skip to content

usb_cam::formats::pixel_format_base

Base pixel format class. Provide all necessary information for converting between V4L2 and ROS formats. Meant to be overridden if conversion function is required.

#include <pixel_format_base.hpp>

Inherited by usb_cam::formats::M4202RGB, usb_cam::formats::MJPEG2RGB, usb_cam::formats::MONO16, usb_cam::formats::MONO8, usb_cam::formats::RAW_MJPEG, usb_cam::formats::RGB8, usb_cam::formats::UYVY, usb_cam::formats::UYVY2RGB, usb_cam::formats::Y102MONO8, usb_cam::formats::YUYV, usb_cam::formats::YUYV2RGB, usb_cam::formats::default_pixel_format

Public Functions

Name
std::string v4l2_str()
String value of V4L2 capture pixel format.
uint32_t v4l2()
Integer value of V4L2 capture pixel format.
std::string ros()
Name of output pixel (encoding) format to ROS.
bool requires_conversion()
True if the current pixel format requires a call to the convert method Used in the usb_cam library logic to determine if a plain memcopy call can be used instead of a call to the convert method of this class.
pixel_format_base(std::string name, uint32_t v4l2, std::string ros, uint8_t channels, uint8_t bit_depth, bool requires_conversion)
std::string name()
Name of pixel format. Used in the parameters file to select this format.
bool is_mono()
Returns if the final output format is monocolor (gray) Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.
bool is_color()
Returns if the final output format is color Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.
bool is_bayer()
Returns if the final output format is bayer Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.
bool has_alpha()
Returns if the final output format has an alpha value Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.
virtual void convert(const char & src, char & dest, const int & bytes_used)
Conversion method. Meant to be overridden if pixel format requires it.
uint8_t channels()
Number of channels (e.g. bytes) per pixel.
uint8_t byte_depth()
Number of bytes per channel.
uint8_t bit_depth()
Number for bit depth of image.

Protected Attributes

Name
uint32_t m_v4l2
Integer correspoding to a specific V4L2_PIX_FMT_* constant See linux/videodev2.h for a list of all possible values for here.
std::string m_ros
This should match ROS encoding string See sensor_msgs/image_encodings.hpp for corresponding possible values. Copy of those values are stored in [usb_cam/constants.hpp]
bool m_requires_conversion
boolean whether or not the current format requires a call to convert. Setting this to true requires that the virtual convert method is implemented.
std::string m_name
Unique name for this pixel format.
uint8_t m_channels
Number of channels (aka bytes per pixel) of output (ROS format above)
uint8_t m_bit_depth
Bitdepth of output (ROS format above)

Public Functions Documentation

function v4l2_str

inline std::string v4l2_str()

String value of V4L2 capture pixel format.

Return: std::string V4L2 capture pixel format

function v4l2

inline uint32_t v4l2()

Integer value of V4L2 capture pixel format.

Return: uint32_t V4L2 capture pixel format

function ros

inline std::string ros()

Name of output pixel (encoding) format to ROS.

Return:

function requires_conversion

inline bool requires_conversion()

True if the current pixel format requires a call to the convert method Used in the usb_cam library logic to determine if a plain memcopy call can be used instead of a call to the convert method of this class.

Return:

function pixel_format_base

inline pixel_format_base(
    std::string name,
    uint32_t v4l2,
    std::string ros,
    uint8_t channels,
    uint8_t bit_depth,
    bool requires_conversion
)

function name

inline std::string name()

Name of pixel format. Used in the parameters file to select this format.

Return:

function is_mono

inline bool is_mono()

Returns if the final output format is monocolor (gray) Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.

Return:

function is_color

inline bool is_color()

Returns if the final output format is color Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.

Return:

function is_bayer

inline bool is_bayer()

Returns if the final output format is bayer Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.

Return:

function has_alpha

inline bool has_alpha()

Returns if the final output format has an alpha value Copied from: https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/include/sensor_msgs/image_encodings.hpp.

Return:

function convert

inline virtual void convert(
    const char *& src,
    char *& dest,
    const int & bytes_used
)

Conversion method. Meant to be overridden if pixel format requires it.

Reimplemented by: usb_cam::formats::M4202RGB::convert, usb_cam::formats::MJPEG2RGB::convert, usb_cam::formats::Y102MONO8::convert, usb_cam::formats::UYVY2RGB::convert, usb_cam::formats::YUYV2RGB::convert

function channels

inline uint8_t channels()

Number of channels (e.g. bytes) per pixel.

Return:

function byte_depth

inline uint8_t byte_depth()

Number of bytes per channel.

function bit_depth

inline uint8_t bit_depth()

Number for bit depth of image.

Return:

Protected Attributes Documentation

variable m_v4l2

uint32_t m_v4l2;

Integer correspoding to a specific V4L2_PIX_FMT_* constant See linux/videodev2.h for a list of all possible values for here.

variable m_ros

std::string m_ros;

This should match ROS encoding string See sensor_msgs/image_encodings.hpp for corresponding possible values. Copy of those values are stored in [usb_cam/constants.hpp]

variable m_requires_conversion

bool m_requires_conversion;

boolean whether or not the current format requires a call to convert. Setting this to true requires that the virtual convert method is implemented.

variable m_name

std::string m_name;

Unique name for this pixel format.

variable m_channels

uint8_t m_channels;

Number of channels (aka bytes per pixel) of output (ROS format above)

variable m_bit_depth

uint8_t m_bit_depth;

Bitdepth of output (ROS format above)


Updated on 2024-05-01 at 16:56:02 +0000