UnderwaterCameraROSPlugin
class gazebo::UnderwaterCameraROSPlugin
¶
class gazebo::UnderwaterCameraROSPlugin : public DepthCameraPlugin : public GazeboRosCameraUtils
Summary¶
Members | Descriptions |
---|---|
public UnderwaterCameraROSPlugin () |
Class constructor. |
public virtual ~UnderwaterCameraROSPlugin () |
Class destructor. |
public void Load (sensors::SensorPtr _sensor,sdf::ElementPtr _sdf) |
Load plugin and its configuration from sdf. |
public virtual void OnNewDepthFrame (const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
|
public virtual void OnNewRGBPointCloud (const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
Update the controller. |
public virtual void OnNewImageFrame (const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
|
protected const float * lastDepth |
Temporarily store pointer to previous depth image. |
protected unsigned char * lastImage |
Latest simulated image. |
protected float * depth2rangeLUT |
Depth to range lookup table (LUT) |
protected float attenuation |
Attenuation constants per channel (RGB) |
protected unsigned char background |
Background constants per channel (RGB) |
protected virtual void SimulateUnderwater (const cv::Mat & _inputImage,const cv::Mat & _inputDepth,cv::Mat & _outputImage) |
Add underwater light damping to image. |
Members¶
public
UnderwaterCameraROSPlugin
()
¶
Class constructor.
public virtual
~UnderwaterCameraROSPlugin
()
¶
Class destructor.
public void
Load
(sensors::SensorPtr _sensor,sdf::ElementPtr _sdf)
¶
Load plugin and its configuration from sdf.
public virtual void
OnNewDepthFrame
(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
public virtual void
OnNewRGBPointCloud
(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
Update the controller.
public virtual void
OnNewImageFrame
(const unsigned char * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)
¶
protected const float *
lastDepth
¶
Temporarily store pointer to previous depth image.
protected unsigned char *
lastImage
¶
Latest simulated image.
protected float *
depth2rangeLUT
¶
Depth to range lookup table (LUT)
protected float
attenuation
¶
Attenuation constants per channel (RGB)
protected unsigned char
background
¶
Background constants per channel (RGB)
protected virtual void
SimulateUnderwater
(const cv::Mat & _inputImage,const cv::Mat & _inputDepth,cv::Mat & _outputImage)
¶
Add underwater light damping to image.