Class Camera

Inheritance Relationships

Base Types

Class Documentation

class Camera : public as2::sensors::TFStatic, protected as2::sensors::GenericSensor

Class to handle the camera sensor.

Public Functions

Camera(const std::string &id, as2::Node *node_ptr, const float pub_freq = -1.0f, bool add_sensor_measurements_base = true, const std::string &info_name = "camera_info", const std::string &camera_link = "camera_link")

Construct a new Camera object.

Parameters:
  • idCamera ID

  • node_ptr – Pointer to the node

  • pub_freq – Frequency to publish the data (-1 to publish every time updateData is called)

  • add_sensor_measurements_base – Add “sensor_measurements” to the topic name

  • info_name – Name of the camera info topic

  • camera_link – Name of the camera link frame

virtual ~Camera()

Destroy the Camera object.

void updateData(const sensor_msgs::msg::Image &img)

Update the data of the camera.

Parameters:

img – Image message

void updateData(const cv::Mat &img)

Update the data of the camera.

Parameters:

img – Image message

void setParameters(const sensor_msgs::msg::CameraInfo &camera_info, const std::string &encoding, const std::string &camera_model = "pinhole")

Set camera info parameters.

Parameters:
  • camera_infoCamera info message

  • encoding – Image encoding

  • camera_modelCamera model (default is “pinhole”)

virtual void setStaticTransform(const std::string &frame_id, const std::string &parent_frame_id, float x, float y, float z, float qx, float qy, float qz, float qw)

Set the Static Transform in TF.

Parameters:
  • frame_id – Frame ID

  • parent_frame_id – Parent Frame ID

  • x – X position (m)

  • y – Y position (m)

  • z – Z position (m)

  • qx – Quaternion X

  • qy – Quaternion Y

  • qz – Quaternion Z

  • qw – Quaternion W

virtual void setStaticTransform(const std::string &frame_id, const std::string &parent_frame_id, float x, float y, float z, float roll, float pitch, float yaw)

Set the Static Transform in TF.

Parameters:
  • frame_id – Frame ID

  • parent_frame_id – Parent Frame ID

  • x – X position (m)

  • y – Y position (m)

  • z – Z position (m)

  • roll – Roll (rad)

  • pitch – Pitch (rad)

  • yaw – Yaw (rad)