usb_cam::UsbCam
Public Functions
Name | |
---|---|
~UsbCam() | |
std::vector< capture_format_t > | supported_formats() |
void | stop_capturing() |
void | start_capturing() |
void | start() Start the configured device. |
void | shutdown(void ) shutdown camera |
bool | set_v4l_parameter(const std::string & param, int value) |
bool | set_v4l_parameter(const std::string & param, const std::string & value) |
bool | set_pixel_format(const formats::format_arguments_t & args) Check if the given format is supported by this device If it is supported, set the m_pixel_format variable to it. |
std::shared_ptr< pixel_format_base > | set_pixel_format(const parameters_t & parameters) Set pixel format from parameter list. Required to have logic within UsbCam object in case pixel format class requires additional information for conversion function (e.g. number of pixels, width, height, etc.) |
bool | set_auto_focus(int value) |
unsigned int | number_of_buffers() |
bool | is_capturing() |
std::vector< capture_format_t > | get_supported_formats() |
std::shared_ptr< pixel_format_base > | get_pixel_format() |
usb_cam::utils::io_method_t | get_io_method() |
size_t | get_image_width() |
timespec | get_image_timestamp() |
unsigned int | get_image_step() Get number of bytes per line in image. |
size_t | get_image_size_in_pixels() |
size_t | get_image_size_in_bytes() |
size_t | get_image_height() |
char * | get_image() Take a new image with device and return it To copy the returned image to another format: sensor_msgs::msg::Image image_msg; auto new_image = get_image(); image_msg.data.resize(step * height); memcpy(&image_msg.data[0], new_image->frame.base, image_msg.data.size());. |
void | get_image(char * destination) Overload of get_image to allow users to pass in an image pointer to fill in. |
int | get_fd() |
time_t | get_epoch_time_shift_us() |
std::string | get_device_name() |
std::shared_ptr< usb_cam::utils::buffer[]> | get_buffers() |
AVDictionary * | get_avoptions() |
AVFrame * | get_avframe() |
AVCodecContext * | get_avcodec_context() |
AVCodec * | get_avcodec() |
void | configure(parameters_t & parameters, const io_method_t & io_method) Configure device, should be called before start. |
UsbCam() |
Public Functions Documentation
function ~UsbCam
~UsbCam()
function supported_formats
inline std::vector< capture_format_t > supported_formats()
function stop_capturing
void stop_capturing()
function start_capturing
void start_capturing()
function start
void start()
Start the configured device.
function shutdown
void shutdown(
void
)
shutdown camera
function set_v4l_parameter
bool set_v4l_parameter(
const std::string & param,
int value
)
function set_v4l_parameter
bool set_v4l_parameter(
const std::string & param,
const std::string & value
)
function set_pixel_format
inline bool set_pixel_format(
const formats::format_arguments_t & args
)
Check if the given format is supported by this device If it is supported, set the m_pixel_format variable to it.
Parameters:
- format the format to check if it is supported
Return: bool true if the given format is supported, false otherwise
function set_pixel_format
inline std::shared_ptr< pixel_format_base > set_pixel_format(
const parameters_t & parameters
)
Set pixel format from parameter list. Required to have logic within UsbCam object in case pixel format class requires additional information for conversion function (e.g. number of pixels, width, height, etc.)
Parameters:
- parameters list of parameters from which the pixel format is to be set
Return: pixel format structure corresponding to a given name
function set_auto_focus
bool set_auto_focus(
int value
)
function number_of_buffers
inline unsigned int number_of_buffers()
function is_capturing
inline bool is_capturing()
function get_supported_formats
std::vector< capture_format_t > get_supported_formats()
function get_pixel_format
inline std::shared_ptr< pixel_format_base > get_pixel_format()
function get_io_method
inline usb_cam::utils::io_method_t get_io_method()
function get_image_width
inline size_t get_image_width()
function get_image_timestamp
inline timespec get_image_timestamp()
function get_image_step
inline unsigned int get_image_step()
Get number of bytes per line in image.
Return: number of bytes per line in image
function get_image_size_in_pixels
inline size_t get_image_size_in_pixels()
function get_image_size_in_bytes
inline size_t get_image_size_in_bytes()
function get_image_height
inline size_t get_image_height()
function get_image
char * get_image()
Take a new image with device and return it To copy the returned image to another format: sensor_msgs::msg::Image image_msg; auto new_image = get_image(); image_msg.data.resize(step * height); memcpy(&image_msg.data[0], new_image->frame.base, image_msg.data.size());.
function get_image
void get_image(
char * destination
)
Overload of get_image to allow users to pass in an image pointer to fill in.
function get_fd
inline int get_fd()
function get_epoch_time_shift_us
inline time_t get_epoch_time_shift_us()
function get_device_name
inline std::string get_device_name()
function get_buffers
inline std::shared_ptr< usb_cam::utils::buffer[]> get_buffers()
function get_avoptions
inline AVDictionary * get_avoptions()
function get_avframe
inline AVFrame * get_avframe()
function get_avcodec_context
inline AVCodecContext * get_avcodec_context()
function get_avcodec
inline AVCodec * get_avcodec()
function configure
void configure(
parameters_t & parameters,
const io_method_t & io_method
)
Configure device, should be called before start.
function UsbCam
UsbCam()
Updated on 2024-06-22 at 03:15:44 +0000