UnderwaterCameraROSPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef __UUV_UNDERWATER_CAMERA_ROS_PLUGIN_HH__
17 #define __UUV_UNDERWATER_CAMERA_ROS_PLUGIN_HH__
18 
19 #include <gazebo/gazebo.hh>
20 #include <ros/ros.h>
21 #include <gazebo/common/Plugin.hh>
22 #include <gazebo/plugins/DepthCameraPlugin.hh>
25 #include <opencv2/opencv.hpp>
26 
27 namespace gazebo
28 {
30  public DepthCameraPlugin, public GazeboRosCameraUtils
31  {
33  public: UnderwaterCameraROSPlugin();
34 
36  public: virtual ~UnderwaterCameraROSPlugin();
37 
39  public: void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
40 
41  public: virtual void OnNewDepthFrame(const float *_image,
42  unsigned int _width, unsigned int _height, unsigned int _depth,
43  const std::string& _format);
44 
46  public: virtual void OnNewRGBPointCloud(const float *_pcd,
47  unsigned int _width, unsigned int _height, unsigned int _depth,
48  const std::string& _format);
49 
50  public: virtual void OnNewImageFrame(const unsigned char* _image,
51  unsigned int _width, unsigned int _height, unsigned int _depth,
52  const std::string& _format);
53 
55  protected: virtual void SimulateUnderwater(
56  const cv::Mat& _inputImage, const cv::Mat& _inputDepth,
57  cv::Mat& _outputImage);
58 
60  protected: const float * lastDepth;
61 
63  protected: unsigned char * lastImage;
64 
66  protected: float* depth2rangeLUT;
67 
69  protected: float attenuation[3];
70 
72  protected: unsigned char background[3];
73  };
74 }
75 
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)
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.


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:33