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

#include <gazebo_ros_image_sonar.hh>

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

Public Member Functions

virtual void Advertise ()
 Advertise point cloud and depth image. More...
 
 GazeboRosImageSonar ()
 Constructor. More...
 
virtual void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin. More...
 
 ~GazeboRosImageSonar ()
 Destructor. More...
 

Protected Member Functions

virtual void OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
virtual void OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
virtual void PublishCameraInfo ()
 

Protected Attributes

std::vector< int > angle_nbr_indices_
 
std::vector< std::vector< int > > angle_range_indices_
 
unsigned int depth
 
ros::Publisher depth_image_camera_info_pub_
 
rendering::DepthCameraPtr depthCamera
 
cv::Mat dist_matrix_
 
std::string format
 
unsigned int height
 
sensors::DepthCameraSensorPtr parentSensor
 
unsigned int width
 

Private Member Functions

void ApplyMedianFilter (cv::Mat &scan)
 
void ApplySmoothing (cv::Mat &scan, float fov)
 
void ApplySpeckleNoise (cv::Mat &scan, float fov)
 
cv::Mat ComputeNormalImage (cv::Mat &depth)
 
void ComputeSonarImage (const float *_src)
 push depth image data into ros topic More...
 
cv::Mat ConstructScanImage (cv::Mat &depth, cv::Mat &SNR)
 
cv::Mat ConstructSonarImage (cv::Mat &depth, cv::Mat &normals)
 
cv::Mat ConstructVisualScanImage (cv::Mat &raw_scan)
 
void DepthImageConnect ()
 
void DepthImageDisconnect ()
 
void DepthInfoConnect ()
 
void DepthInfoDisconnect ()
 
void FillDepthImage (const float *_src)
 push depth image data into ros topic More...
 
bool FillDepthImageHelper (sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
 
bool FillPointCloudHelper (sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
 
void FillPointdCloud (const float *_src)
 Put camera data to the ROS topic. More...
 
void InfoConnect ()
 
void InfoDisconnect ()
 
void MultibeamImageConnect ()
 
void MultibeamImageDisconnect ()
 
void NormalImageConnect ()
 
void NormalImageDisconnect ()
 
void PointCloudConnect ()
 
void PointCloudDisconnect ()
 
void RawSonarImageConnect ()
 
void RawSonarImageDisconnect ()
 
void SonarImageConnect ()
 
void SonarImageDisconnect ()
 
- Private 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 ()
 
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 ()
 

Private Attributes

std::string depth_image_camera_info_topic_name_
 
int depth_image_connect_count_
 Keep track of number of connctions for point clouds. More...
 
sensor_msgs::Image depth_image_msg_
 
ros::Publisher depth_image_pub_
 
std::string depth_image_topic_name_
 image where each pixel contains the depth information More...
 
int depth_info_connect_count_
 
common::Time depth_sensor_update_time_
 
std::default_random_engine generator
 
common::Time last_depth_image_camera_info_update_time_
 
event::ConnectionPtr load_connection_
 
sensor_msgs::Image multibeam_image_msg_
 
ros::Publisher multibeam_image_pub_
 
event::ConnectionPtr newDepthFrameConnection
 
event::ConnectionPtr newImageFrameConnection
 
event::ConnectionPtr newRGBPointCloudConnection
 
sensor_msgs::Image normal_image_msg_
 
ros::Publisher normal_image_pub_
 
int point_cloud_connect_count_
 Keep track of number of connctions for point clouds. More...
 
double point_cloud_cutoff_
 
sensor_msgs::PointCloud2 point_cloud_msg_
 PointCloud2 point cloud message. More...
 
ros::Publisher point_cloud_pub_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
std::string point_cloud_topic_name_
 ROS image topic name. More...
 
sensor_msgs::Image raw_sonar_image_msg_
 
ros::Publisher raw_sonar_image_pub_
 
sensor_msgs::Image sonar_image_msg_
 
ros::Publisher sonar_image_pub_
 
- Private 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 73 of file gazebo_ros_image_sonar.hh.

Constructor & Destructor Documentation

gazebo::GazeboRosImageSonar::GazeboRosImageSonar ( )

Constructor.

Parameters
parentThe parent entity, must be a Model or a Sensor

Definition at line 60 of file gazebo_ros_image_sonar.cpp.

gazebo::GazeboRosImageSonar::~GazeboRosImageSonar ( )

Destructor.

Definition at line 69 of file gazebo_ros_image_sonar.cpp.

Member Function Documentation

void gazebo::GazeboRosImageSonar::Advertise ( )
virtual

Advertise point cloud and depth image.

Definition at line 171 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::ApplyMedianFilter ( cv::Mat &  scan)
private

Definition at line 838 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::ApplySmoothing ( cv::Mat &  scan,
float  fov 
)
private

Definition at line 770 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::ApplySpeckleNoise ( cv::Mat &  scan,
float  fov 
)
private

Definition at line 754 of file gazebo_ros_image_sonar.cpp.

cv::Mat gazebo::GazeboRosImageSonar::ComputeNormalImage ( cv::Mat &  depth)
private

Definition at line 635 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::ComputeSonarImage ( const float *  _src)
private

push depth image data into ros topic

Definition at line 972 of file gazebo_ros_image_sonar.cpp.

cv::Mat gazebo::GazeboRosImageSonar::ConstructScanImage ( cv::Mat &  depth,
cv::Mat &  SNR 
)
private

Definition at line 851 of file gazebo_ros_image_sonar.cpp.

cv::Mat gazebo::GazeboRosImageSonar::ConstructSonarImage ( cv::Mat &  depth,
cv::Mat &  normals 
)
private

Definition at line 707 of file gazebo_ros_image_sonar.cpp.

cv::Mat gazebo::GazeboRosImageSonar::ConstructVisualScanImage ( cv::Mat &  raw_scan)
private

Definition at line 909 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::DepthImageConnect ( )
private

Definition at line 251 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::DepthImageDisconnect ( )
private

Definition at line 258 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::DepthInfoConnect ( )
private

Definition at line 321 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::DepthInfoDisconnect ( )
private

Definition at line 327 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::FillDepthImage ( const float *  _src)
private

push depth image data into ros topic

copy from depth to depth image message

Definition at line 492 of file gazebo_ros_image_sonar.cpp.

bool gazebo::GazeboRosImageSonar::FillDepthImageHelper ( sensor_msgs::Image &  image_msg,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
)
private

Definition at line 597 of file gazebo_ros_image_sonar.cpp.

bool gazebo::GazeboRosImageSonar::FillPointCloudHelper ( sensor_msgs::PointCloud2 &  point_cloud_msg,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
)
private

Definition at line 514 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::FillPointdCloud ( const float *  _src)
private

Put camera data to the ROS topic.

copy from depth to point cloud message

Definition at line 467 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::InfoConnect ( )
private
void gazebo::GazeboRosImageSonar::InfoDisconnect ( )
private
void gazebo::GazeboRosImageSonar::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Load the plugin.

Parameters
takein SDF root element

Definition at line 81 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::MultibeamImageConnect ( )
private

Definition at line 279 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::MultibeamImageDisconnect ( )
private

Definition at line 286 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::NormalImageConnect ( )
private

Definition at line 265 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::NormalImageDisconnect ( )
private

Definition at line 272 of file gazebo_ros_image_sonar.cpp.

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

Update the controller.

Definition at line 334 of file gazebo_ros_image_sonar.cpp.

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

Update the controller.

Definition at line 438 of file gazebo_ros_image_sonar.cpp.

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

Update the controller.

Definition at line 372 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::PointCloudConnect ( )
private

Definition at line 233 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::PointCloudDisconnect ( )
private

Definition at line 241 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::PublishCameraInfo ( )
protectedvirtual

Definition at line 1012 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::RawSonarImageConnect ( )
private

Definition at line 307 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::RawSonarImageDisconnect ( )
private

Definition at line 314 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::SonarImageConnect ( )
private

Definition at line 293 of file gazebo_ros_image_sonar.cpp.

void gazebo::GazeboRosImageSonar::SonarImageDisconnect ( )
private

Definition at line 300 of file gazebo_ros_image_sonar.cpp.

Member Data Documentation

std::vector<int> gazebo::GazeboRosImageSonar::angle_nbr_indices_
protected

Definition at line 195 of file gazebo_ros_image_sonar.hh.

std::vector<std::vector<int> > gazebo::GazeboRosImageSonar::angle_range_indices_
protected

Definition at line 194 of file gazebo_ros_image_sonar.hh.

unsigned int gazebo::GazeboRosImageSonar::depth
protected

Definition at line 189 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::depth_image_camera_info_pub_
protected

Definition at line 184 of file gazebo_ros_image_sonar.hh.

std::string gazebo::GazeboRosImageSonar::depth_image_camera_info_topic_name_
private

Definition at line 177 of file gazebo_ros_image_sonar.hh.

int gazebo::GazeboRosImageSonar::depth_image_connect_count_
private

Keep track of number of connctions for point clouds.

Definition at line 126 of file gazebo_ros_image_sonar.hh.

sensor_msgs::Image gazebo::GazeboRosImageSonar::depth_image_msg_
private

Definition at line 157 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::depth_image_pub_
private

Definition at line 149 of file gazebo_ros_image_sonar.hh.

std::string gazebo::GazeboRosImageSonar::depth_image_topic_name_
private

image where each pixel contains the depth information

Definition at line 176 of file gazebo_ros_image_sonar.hh.

int gazebo::GazeboRosImageSonar::depth_info_connect_count_
private

Definition at line 178 of file gazebo_ros_image_sonar.hh.

common::Time gazebo::GazeboRosImageSonar::depth_sensor_update_time_
private

Definition at line 183 of file gazebo_ros_image_sonar.hh.

rendering::DepthCameraPtr gazebo::GazeboRosImageSonar::depthCamera
protected

Definition at line 198 of file gazebo_ros_image_sonar.hh.

cv::Mat gazebo::GazeboRosImageSonar::dist_matrix_
protected

Definition at line 193 of file gazebo_ros_image_sonar.hh.

std::string gazebo::GazeboRosImageSonar::format
protected

Definition at line 190 of file gazebo_ros_image_sonar.hh.

std::default_random_engine gazebo::GazeboRosImageSonar::generator
private

Definition at line 167 of file gazebo_ros_image_sonar.hh.

unsigned int gazebo::GazeboRosImageSonar::height
protected

Definition at line 189 of file gazebo_ros_image_sonar.hh.

common::Time gazebo::GazeboRosImageSonar::last_depth_image_camera_info_update_time_
private

Definition at line 137 of file gazebo_ros_image_sonar.hh.

event::ConnectionPtr gazebo::GazeboRosImageSonar::load_connection_
private

Definition at line 186 of file gazebo_ros_image_sonar.hh.

sensor_msgs::Image gazebo::GazeboRosImageSonar::multibeam_image_msg_
private

Definition at line 159 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::multibeam_image_pub_
private

Definition at line 151 of file gazebo_ros_image_sonar.hh.

event::ConnectionPtr gazebo::GazeboRosImageSonar::newDepthFrameConnection
private

Definition at line 200 of file gazebo_ros_image_sonar.hh.

event::ConnectionPtr gazebo::GazeboRosImageSonar::newImageFrameConnection
private

Definition at line 202 of file gazebo_ros_image_sonar.hh.

event::ConnectionPtr gazebo::GazeboRosImageSonar::newRGBPointCloudConnection
private

Definition at line 201 of file gazebo_ros_image_sonar.hh.

sensor_msgs::Image gazebo::GazeboRosImageSonar::normal_image_msg_
private

Definition at line 158 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::normal_image_pub_
private

Definition at line 150 of file gazebo_ros_image_sonar.hh.

sensors::DepthCameraSensorPtr gazebo::GazeboRosImageSonar::parentSensor
protected

Definition at line 197 of file gazebo_ros_image_sonar.hh.

int gazebo::GazeboRosImageSonar::point_cloud_connect_count_
private

Keep track of number of connctions for point clouds.

Definition at line 121 of file gazebo_ros_image_sonar.hh.

double gazebo::GazeboRosImageSonar::point_cloud_cutoff_
private

Definition at line 163 of file gazebo_ros_image_sonar.hh.

sensor_msgs::PointCloud2 gazebo::GazeboRosImageSonar::point_cloud_msg_
private

PointCloud2 point cloud message.

Definition at line 156 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::point_cloud_pub_
private

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 148 of file gazebo_ros_image_sonar.hh.

std::string gazebo::GazeboRosImageSonar::point_cloud_topic_name_
private

ROS image topic name.

Definition at line 166 of file gazebo_ros_image_sonar.hh.

sensor_msgs::Image gazebo::GazeboRosImageSonar::raw_sonar_image_msg_
private

Definition at line 161 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::raw_sonar_image_pub_
private

Definition at line 153 of file gazebo_ros_image_sonar.hh.

sensor_msgs::Image gazebo::GazeboRosImageSonar::sonar_image_msg_
private

Definition at line 160 of file gazebo_ros_image_sonar.hh.

ros::Publisher gazebo::GazeboRosImageSonar::sonar_image_pub_
private

Definition at line 152 of file gazebo_ros_image_sonar.hh.

unsigned int gazebo::GazeboRosImageSonar::width
protected

Definition at line 189 of file gazebo_ros_image_sonar.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 Thu Jun 18 2020 03:28:33