Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::UnderwaterCameraROSPlugin Class Reference

#include <UnderwaterCameraROSPlugin.hh>

Inheritance diagram for gazebo::UnderwaterCameraROSPlugin:
Inheritance graph
[legend]

Public Member Functions

void Load (sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
 Load plugin and its configuration from sdf. More...
 
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)
 
virtual void OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
 UnderwaterCameraROSPlugin ()
 Class constructor. More...
 
virtual ~UnderwaterCameraROSPlugin ()
 Class destructor. More...
 
- Public Member Functions inherited from gazebo::GazeboRosCameraUtils
 GazeboRosCameraUtils ()
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline)
 
event::ConnectionPtr OnLoad (const boost::function< void()> &)
 
 ~GazeboRosCameraUtils ()
 

Protected Member Functions

virtual void SimulateUnderwater (const cv::Mat &_inputImage, const cv::Mat &_inputDepth, cv::Mat &_outputImage)
 Add underwater light damping to image. More...
 
- Protected Member Functions inherited from gazebo::GazeboRosCameraUtils
void CameraQueueThread ()
 
virtual bool CanTriggerCamera ()
 
void ImageConnect ()
 
void ImageDisconnect ()
 
void PublishCameraInfo ()
 
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 
void PublishCameraInfo (common::Time &last_update_time)
 
void PutCameraData (const unsigned char *_src)
 
void PutCameraData (const unsigned char *_src, common::Time &last_update_time)
 
virtual void TriggerCamera ()
 

Protected Attributes

float attenuation [3]
 Attenuation constants per channel (RGB) More...
 
unsigned char background [3]
 Background constants per channel (RGB) More...
 
float * depth2rangeLUT
 Depth to range lookup table (LUT) More...
 
const float * lastDepth
 Temporarily store pointer to previous depth image. More...
 
unsigned char * lastImage
 Latest simulated image. More...
 
- Protected Attributes inherited from gazebo::GazeboRosCameraUtils
bool border_crop_
 
boost::thread callback_queue_thread_
 
rendering::CameraPtr camera_
 
boost::shared_ptr< camera_info_manager::CameraInfoManagercamera_info_manager_
 
ros::Publisher camera_info_pub_
 
std::string camera_info_topic_name_
 
ros::CallbackQueue camera_queue_
 
double cx_
 
double cx_prime_
 
double cy_
 
unsigned int depth_
 
double distortion_k1_
 
double distortion_k2_
 
double distortion_k3_
 
double distortion_t1_
 
double distortion_t2_
 
double focal_length_
 
std::string format_
 
std::string frame_name_
 
double hack_baseline_
 
unsigned int height_
 
boost::shared_ptr< int > image_connect_count_
 
boost::shared_ptr< boost::mutex > image_connect_count_lock_
 
sensor_msgs::Image image_msg_
 
image_transport::Publisher image_pub_
 
std::string image_topic_name_
 
bool initialized_
 
common::Time last_info_update_time_
 
common::Time last_update_time_
 
boost::mutex lock_
 
sensors::SensorPtr parentSensor_
 
ros::NodeHandlerosnode_
 
common::Time sensor_update_time_
 
int skip_
 
std::string trigger_topic_name_
 
std::string type_
 
double update_period_
 
double update_rate_
 
boost::shared_ptr< bool > was_active_
 
unsigned int width_
 
physics::WorldPtr world
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 29 of file UnderwaterCameraROSPlugin.hh.

Constructor & Destructor Documentation

gazebo::UnderwaterCameraROSPlugin::UnderwaterCameraROSPlugin ( )

Class constructor.

Definition at line 21 of file UnderwaterCameraROSPlugin.cc.

gazebo::UnderwaterCameraROSPlugin::~UnderwaterCameraROSPlugin ( )
virtual

Class destructor.

Definition at line 26 of file UnderwaterCameraROSPlugin.cc.

Member Function Documentation

void gazebo::UnderwaterCameraROSPlugin::Load ( sensors::SensorPtr  _sensor,
sdf::ElementPtr  _sdf 
)

Load plugin and its configuration from sdf.

Definition at line 36 of file UnderwaterCameraROSPlugin.cc.

void gazebo::UnderwaterCameraROSPlugin::OnNewDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
virtual

Definition at line 121 of file UnderwaterCameraROSPlugin.cc.

void gazebo::UnderwaterCameraROSPlugin::OnNewImageFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
virtual

Definition at line 136 of file UnderwaterCameraROSPlugin.cc.

void gazebo::UnderwaterCameraROSPlugin::OnNewRGBPointCloud ( const float *  _pcd,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
virtual

Update the controller.

Definition at line 130 of file UnderwaterCameraROSPlugin.cc.

void gazebo::UnderwaterCameraROSPlugin::SimulateUnderwater ( const cv::Mat &  _inputImage,
const cv::Mat &  _inputDepth,
cv::Mat &  _outputImage 
)
protectedvirtual

Add underwater light damping to image.

Definition at line 176 of file UnderwaterCameraROSPlugin.cc.

Member Data Documentation

float gazebo::UnderwaterCameraROSPlugin::attenuation[3]
protected

Attenuation constants per channel (RGB)

Definition at line 69 of file UnderwaterCameraROSPlugin.hh.

unsigned char gazebo::UnderwaterCameraROSPlugin::background[3]
protected

Background constants per channel (RGB)

Definition at line 72 of file UnderwaterCameraROSPlugin.hh.

float* gazebo::UnderwaterCameraROSPlugin::depth2rangeLUT
protected

Depth to range lookup table (LUT)

Definition at line 66 of file UnderwaterCameraROSPlugin.hh.

const float* gazebo::UnderwaterCameraROSPlugin::lastDepth
protected

Temporarily store pointer to previous depth image.

Definition at line 60 of file UnderwaterCameraROSPlugin.hh.

unsigned char* gazebo::UnderwaterCameraROSPlugin::lastImage
protected

Latest simulated image.

Definition at line 63 of file UnderwaterCameraROSPlugin.hh.


The documentation for this class was generated from the following files:


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:20