Class Camera
Defined in File sensor.hpp
Inheritance Relationships
Base Types
public as2::sensors::TFStatic
(Class TFStatic)protected as2::sensors::GenericSensor
(Class GenericSensor)
Class Documentation
-
class Camera : public as2::sensors::TFStatic, protected as2::sensors::GenericSensor
Class to handle the camera sensor.
Public Functions
-
Camera(as2::Node *node_ptr, const std::string &prefix = "", const float pub_freq = -1.0f, bool add_sensor_measurements_base = true, const std::string &camera_link = "camera_link")
Construct a new Camera object.
- Parameters:
node_ptr – Pointer to the node
prefix – ROS 2 parameter prefix. If not using ROS 2 parameters, give the camera name (e.g. “camera_front”)
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. Default is “camera_info”
camera_link – Name of the camera link frame id. Default is “camera_link”
-
inline Camera(const std::string &prefix, as2::Node *node_ptr, const float pub_freq = -1.0f, bool add_sensor_measurements_base = true, const std::string &camera_link = "camera_link")
Construct a new Camera object. DEPRECATED.
- Parameters:
prefix – ROS 2 parameter prefix. If not using ROS 2 parameters, give the camera name (e.g. “camera_front”)
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. Default is “camera_info”
camera_link – Name of the camera link frame id. Default is “camera_link”
-
inline void setParameters(const sensor_msgs::msg::CameraInfo &camera_info, const std::string &encoding, const std::string &camera_model = "pinhole")
Set Camera parameters. DEPRECATED.
-
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 setCameraInfo(const sensor_msgs::msg::CameraInfo &camera_info)
Set camera info parameters.
- Parameters:
camera_info – Camera info message
-
void setCameraLinkTransform(const std::string &parent_frame_id, const float x, const float y, const float z, const float roll, const float pitch, const float yaw)
Set camera link frame transformation relative to the parent frame.
- Parameters:
parent_frame_id – Parent frame ID (e.g. base_link)
x – X position (m)
y – Y position (m)
z – Z position (m)
roll – Roll (rad)
pitch – Pitch (rad)
yaw – Yaw (rad)
-
void setEncoding(const std::string &encoding)
Set camera encoding.
- Parameters:
encoding – Encoding of the camera
-
void readCameraInfoFromROSParameters(const std::string &prefix = "")
Read camera info from ROS parameters.
- Parameters:
node_ptr – Pointer to the node
prefix – ROS 2 parameter prefix. By default is “”
-
void readCameraTranformFromROSParameters(const std::string &prefix = "")
Read camera transform from ROS parameters.
- Parameters:
node_ptr – Pointer to the node
prefix – ROS 2 parameter prefix. By default is “”
-
Camera(as2::Node *node_ptr, const std::string &prefix = "", const float pub_freq = -1.0f, bool add_sensor_measurements_base = true, const std::string &camera_link = "camera_link")