Skip to content

GazeboRosImageSonar

class gazebo::GazeboRosImageSonar

class gazebo::GazeboRosImageSonar
  : public SensorPlugin
  : private GazeboRosCameraUtils
Summary
Members Descriptions
publicGazeboRosImageSonar() Constructor.
public~GazeboRosImageSonar() Destructor.
public virtual voidLoad(sensors::SensorPtr _parent,sdf::ElementPtr _sdf) Load the plugin.
public virtual voidAdvertise() Advertise point cloud and depth image.
protected ros::Publisherdepth_image_camera_info_pub_
protected unsigned intwidth
protected unsigned intheight
protected unsigned intdepth
protected std::stringformat
protected cv::Matdist_matrix_
protected std::vector< std::vector< int > >angle_range_indices_
protected std::vector< int >angle_nbr_indices_
protected sensors::DepthCameraSensorPtrparentSensor
protected rendering::DepthCameraPtrdepthCamera
protected virtual voidOnNewDepthFrame(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) Update the controller.
protected virtual voidOnNewRGBPointCloud(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) Update the controller.
protected virtual voidOnNewImageFrame(const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) Update the controller.
protected virtual voidPublishCameraInfo()
Members
publicGazeboRosImageSonar()

Constructor.

Parameters
  • parent The parent entity, must be a Model or a Sensor
public~GazeboRosImageSonar()

Destructor.

public virtual voidLoad(sensors::SensorPtr _parent,sdf::ElementPtr _sdf)

Load the plugin.

Parameters
  • take in SDF root element
public virtual voidAdvertise()

Advertise point cloud and depth image.

protected ros::Publisherdepth_image_camera_info_pub_
protected unsigned intwidth
protected unsigned intheight
protected unsigned intdepth
protected std::stringformat
protected cv::Matdist_matrix_
protected std::vector< std::vector< int > >angle_range_indices_
protected std::vector< int >angle_nbr_indices_
protected sensors::DepthCameraSensorPtrparentSensor
protected rendering::DepthCameraPtrdepthCamera
protected virtual voidOnNewDepthFrame(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)

Update the controller.

protected virtual voidOnNewRGBPointCloud(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)

Update the controller.

protected virtual voidOnNewImageFrame(const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)

Update the controller.

protected virtual voidPublishCameraInfo()