Class GazeboRosCamera

Inheritance Relationships

Base Types

  • public gazebo::CameraPlugin

  • private gazebo::DepthCameraPlugin

  • private gazebo_plugins::MultiCameraPlugin (Class MultiCameraPlugin)

Class Documentation

class GazeboRosCamera : public gazebo::CameraPlugin, private gazebo::DepthCameraPlugin, private gazebo_plugins::MultiCameraPlugin

A plugin that publishes raw images and camera info for generic camera sensors. It can also be configured to publish raw depth images, point cloud and camera info for depth camera sensors. Also configurable as multi camera sensor. Example Usage:

<plugin name="plugin_name" filename="libgazebo_ros_camera.so">
  <!-- Change namespace, camera name and topics so:
         Images are published to: /custom_ns/custom_camera/custom_image
         Camera info is published to: /custom_ns/custom_camera/custom_info
         Trigger is received on: /custom_ns/custom_camera/custom_trigger
  -->
  <ros>
    <namespace>custom_ns</namespace>
    <remapping>image_raw:=custom_img</remapping>
    <remapping>camera_info:=custom_info</remapping>
    <remapping>image_trigger:=custom_trigger</remapping>
  </ros>

  <!-- Set camera name. If empty, defaults to sensor name -->
  <camera_name>custom_camera</camera_name>

  <!-- Set TF frame name. If empty, defaults to link name -->
  <frame_name>custom_frame</frame_name>

  <!-- Set to true to turn on triggering -->
  <triggered>true</triggered>

  <!-- Set some projection matrix fields-->
  <!-- Projection matrix principal point cx-->
  <P_cx>0</P_cx>
  <!-- Projection matrix principal point cy-->
  <P_cy>320.5</P_cy>
  <!-- Projection matrix focal length fy-->
  <P_fy>0</P_fy>
  <!-- Projection matrix translation Tx, Ty between stereo cameras-->
  <Tx>240.5</Tx>
  <Ty>0</Ty>
  <!-- Full 3x3 rectification matrix. Values are in row-major order -->
  <rectification_matrix>0.999 0.0 -0.049 0.0 1.0 0.0 0.049 0.0 0.999</rectification_matrix>

  <hack_baseline>0.07</hack_baseline>
</plugin>

Public Functions

GazeboRosCamera()

Constructor.

~GazeboRosCamera()

Destructor.

Protected Functions

virtual void Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) override
void NewFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, int camera_num)

Helper to process and publish the image received to appropriate topic.

void OnNewFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override

Callback when camera produces a new image.

void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override

Callback when depth camera produces a new image.

void OnNewDepthFrame(const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override

Callback when camera produces a new depth image.

virtual void OnNewMultiFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format, const int _camera_num) override

Callback when multi camera produces a new image.

void OnTrigger(const std_msgs::msg::Empty::SharedPtr _dummy)

Callback when camera is triggered.

void PreRender()

Callback on pre-render event.

void SetCameraEnabled(const bool _enabled)

Enables or disables the camera so it produces messages or not. param[in] _enabled True to enable.

std::vector<gazebo::rendering::CameraPtr> GetCameras() const
std::string GetCameraName() const
uint64_t GetNumCameras() const
gazebo_ros::Node::SharedPtr GetRosNode() const

Get the ROS node associated with this plugin The returned pointer is null if the plugin has not been loaded.