Class VimbaXCamera::Frame

Nested Relationships

This class is a nested type of Class VimbaXCamera.

Inheritance Relationships

Base Types

  • public sensor_msgs::msg::Image

  • public std::enable_shared_from_this< Frame >

Class Documentation

class Frame : public sensor_msgs::msg::Image, public std::enable_shared_from_this<Frame>

Public Functions

~Frame()
Frame(const Frame&) = delete
Frame &operator=(const Frame&) = delete
void set_callback(std::function<void(std::shared_ptr<Frame>)> callback)
int32_t queue() const
std::string get_image_encoding() const
int64_t get_frame_id() const
uint64_t get_timestamp_ns() const
void on_frame_ready()

Public Static Functions

static result<std::shared_ptr<Frame>> create(std::shared_ptr<VimbaXCamera> camera, size_t size, size_t alignment = 1)