Class UsbCam
Defined in File usb_cam.hpp
Class Documentation
-
class UsbCam
Public Functions
-
UsbCam()
-
~UsbCam()
-
void configure(parameters_t ¶meters, const io_method_t &io_method)
Configure device, should be called before start.
-
void start()
Start the configured device.
-
void shutdown(void)
shutdown camera
-
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.
-
std::vector<capture_format_t> get_supported_formats()
-
bool set_auto_focus(int value)
-
bool set_v4l_parameter(const std::string ¶m, int value)
-
bool set_v4l_parameter(const std::string ¶m, const std::string &value)
-
void stop_capturing()
-
void start_capturing()
-
inline size_t get_image_width()
-
inline size_t get_image_height()
-
inline size_t get_image_size_in_bytes()
-
inline size_t get_image_size_in_pixels()
-
inline timespec get_image_timestamp()
-
inline unsigned int get_image_step()
Get number of bytes per line in image.
- Returns:
number of bytes per line in image
-
inline std::string get_device_name()
-
inline std::shared_ptr<pixel_format_base> get_pixel_format()
-
inline usb_cam::utils::io_method_t get_io_method()
-
inline int get_fd()
-
inline unsigned int number_of_buffers()
-
inline AVCodec *get_avcodec()
-
inline AVDictionary *get_avoptions()
-
inline AVCodecContext *get_avcodec_context()
-
inline AVFrame *get_avframe()
-
inline bool is_capturing()
-
inline time_t get_epoch_time_shift_us()
-
inline std::vector<capture_format_t> supported_formats()
-
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
- Returns:
bool true if the given format is supported, false otherwise
-
inline std::shared_ptr<pixel_format_base> set_pixel_format(const parameters_t ¶meters)
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
- Returns:
pixel format structure corresponding to a given name
-
UsbCam()