UnderwaterCameraROSPlugin
class gazebo::UnderwaterCameraROSPlugin¶
class gazebo::UnderwaterCameraROSPlugin : public DepthCameraPlugin : public GazeboRosCameraUtils
Summary¶
| Members | Descriptions |
|---|---|
publicUnderwaterCameraROSPlugin() |
Class constructor. |
public virtual~UnderwaterCameraROSPlugin() |
Class destructor. |
public voidLoad(sensors::SensorPtr _sensor,sdf::ElementPtr _sdf) |
Load plugin and its configuration from sdf. |
public virtual voidOnNewDepthFrame(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
|
public virtual voidOnNewRGBPointCloud(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format) |
Update the controller. |
public virtual voidOnNewImageFrame(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 floatattenuation |
Attenuation constants per channel (RGB) |
protected unsigned charbackground |
Background constants per channel (RGB) |
protected virtual voidSimulateUnderwater(const cv::Mat & _inputImage,const cv::Mat & _inputDepth,cv::Mat & _outputImage) |
Add underwater light damping to image. |
Members¶
publicUnderwaterCameraROSPlugin()¶
Class constructor.
public virtual~UnderwaterCameraROSPlugin()¶
Class destructor.
public voidLoad(sensors::SensorPtr _sensor,sdf::ElementPtr _sdf)¶
Load plugin and its configuration from sdf.
public virtual voidOnNewDepthFrame(const float * _image,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)¶
public virtual voidOnNewRGBPointCloud(const float * _pcd,unsigned int _width,unsigned int _height,unsigned int _depth,const std::string & _format)¶
Update the controller.
public virtual voidOnNewImageFrame(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 floatattenuation¶
Attenuation constants per channel (RGB)
protected unsigned charbackground¶
Background constants per channel (RGB)
protected virtual voidSimulateUnderwater(const cv::Mat & _inputImage,const cv::Mat & _inputDepth,cv::Mat & _outputImage)¶
Add underwater light damping to image.