GazeboRosImageSonar
class gazebo::GazeboRosImageSonar
¶
class gazebo::GazeboRosImageSonar : public SensorPlugin : private GazeboRosCameraUtils
Summary¶
Members | Descriptions |
---|---|
public GazeboRosImageSonar () |
Constructor. |
public ~GazeboRosImageSonar () |
Destructor. |
public virtual void Load (sensors::SensorPtr _parent,sdf::ElementPtr _sdf) |
Load the plugin. |
public virtual void Advertise () |
Advertise point cloud and depth image. |
protected ros::Publisher depth_image_camera_info_pub_ |
|
protected unsigned int width |
|
protected unsigned int height |
|
protected unsigned int depth |
|
protected std::string format |
|
protected cv::Mat dist_matrix_ |
|
protected std::vector< std::vector< int > > angle_range_indices_ |
|
protected std::vector< int > angle_nbr_indices_ |
|
protected sensors::DepthCameraSensorPtr parentSensor |
|
protected rendering::DepthCameraPtr depthCamera |
|
protected virtual void OnNewDepthFrame (const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
Update the controller. |
protected virtual void OnNewRGBPointCloud (const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
Update the controller. |
protected virtual void OnNewImageFrame (const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
Update the controller. |
protected virtual void PublishCameraInfo () |
Members¶
public
GazeboRosImageSonar
()
¶
Constructor.
Parameters¶
parent
The parent entity, must be a Model or a Sensor
public
~GazeboRosImageSonar
()
¶
Destructor.
public virtual void
Load
(sensors::SensorPtr _parent,sdf::ElementPtr _sdf)
¶
Load the plugin.
Parameters¶
take
in SDF root element
public virtual void
Advertise
()
¶
Advertise point cloud and depth image.
protected ros::Publisher
depth_image_camera_info_pub_
¶
protected unsigned int
width
¶
protected unsigned int
height
¶
protected unsigned int
depth
¶
protected std::string
format
¶
protected cv::Mat
dist_matrix_
¶
protected std::vector< std::vector< int > >
angle_range_indices_
¶
protected std::vector< int >
angle_nbr_indices_
¶
protected sensors::DepthCameraSensorPtr
parentSensor
¶
protected rendering::DepthCameraPtr
depthCamera
¶
protected virtual void
OnNewDepthFrame
(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
Update the controller.
protected virtual void
OnNewRGBPointCloud
(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
Update the controller.
protected virtual void
OnNewImageFrame
(const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
Update the controller.