16 #ifndef __UUV_UNDERWATER_CAMERA_ROS_PLUGIN_HH__ 17 #define __UUV_UNDERWATER_CAMERA_ROS_PLUGIN_HH__ 19 #include <gazebo/gazebo.hh> 21 #include <gazebo/common/Plugin.hh> 22 #include <gazebo/plugins/DepthCameraPlugin.hh> 25 #include <opencv2/opencv.hpp> 39 public:
void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
42 unsigned int _width,
unsigned int _height,
unsigned int _depth,
43 const std::string& _format);
47 unsigned int _width,
unsigned int _height,
unsigned int _depth,
48 const std::string& _format);
51 unsigned int _width,
unsigned int _height,
unsigned int _depth,
52 const std::string& _format);
56 const cv::Mat& _inputImage,
const cv::Mat& _inputDepth,
57 cv::Mat& _outputImage);
76 #endif // __UUV_UNDERWATER_CAMERA_ROS_PLUGIN_HH__ void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
Load plugin and its configuration from sdf.
float attenuation[3]
Attenuation constants per channel (RGB)
UnderwaterCameraROSPlugin()
Class constructor.
unsigned char background[3]
Background constants per channel (RGB)
virtual void OnNewRGBPointCloud(const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
virtual void SimulateUnderwater(const cv::Mat &_inputImage, const cv::Mat &_inputDepth, cv::Mat &_outputImage)
Add underwater light damping to image.
float * depth2rangeLUT
Depth to range lookup table (LUT)
virtual void OnNewDepthFrame(const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
unsigned char * lastImage
Latest simulated image.
virtual ~UnderwaterCameraROSPlugin()
Class destructor.
const float * lastDepth
Temporarily store pointer to previous depth image.