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

#include <gazebo_noisydepth_plugin.h>

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

Public Member Functions

virtual void Advertise ()
 Advertise depth image. More...
 
 GazeboNoisyDepth ()
 
virtual void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin. More...
 
virtual void OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 
 ~GazeboNoisyDepth ()
 

Protected Member Functions

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

Private Member Functions

void DepthImageConnect ()
 
void DepthImageDisconnect ()
 
void DepthInfoConnect ()
 
void DepthInfoDisconnect ()
 
void FillDepthImage (const float *_src)
 
bool FillDepthImageHelper (const uint32_t rows_arg, const uint32_t cols_arg, const uint32_t step_arg, const float *data_arg, sensor_msgs::Image *image_msg)
 
virtual void PublishCameraInfo ()
 
- 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

ros::Publisher depth_image_camera_info_pub_
 
std::string depth_image_camera_info_topic_name_
 
int depth_image_connect_count_
 
sensor_msgs::Image depth_image_msg_
 
ros::Publisher depth_image_pub_
 
std::string depth_image_topic_name_
 
int depth_info_connect_count_
 
common::Time depth_sensor_update_time_
 
common::Time last_depth_image_camera_info_update_time_
 
event::ConnectionPtr load_connection_
 
std::unique_ptr< DepthNoiseModelnoise_model
 
- Private Attributes inherited from gazebo::GazeboRosCameraUtils
bool auto_distortion_
 
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< intimage_connect_count_
 
boost::shared_ptr< boost::muteximage_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 59 of file gazebo_noisydepth_plugin.h.

Constructor & Destructor Documentation

◆ GazeboNoisyDepth()

gazebo::GazeboNoisyDepth::GazeboNoisyDepth ( )

Definition at line 40 of file gazebo_noisydepth_plugin.cpp.

◆ ~GazeboNoisyDepth()

gazebo::GazeboNoisyDepth::~GazeboNoisyDepth ( )

Definition at line 46 of file gazebo_noisydepth_plugin.cpp.

Member Function Documentation

◆ Advertise()

void gazebo::GazeboNoisyDepth::Advertise ( )
virtual

Advertise depth image.

Definition at line 157 of file gazebo_noisydepth_plugin.cpp.

◆ DepthImageConnect()

void gazebo::GazeboNoisyDepth::DepthImageConnect ( )
private

Definition at line 177 of file gazebo_noisydepth_plugin.cpp.

◆ DepthImageDisconnect()

void gazebo::GazeboNoisyDepth::DepthImageDisconnect ( )
private

Definition at line 182 of file gazebo_noisydepth_plugin.cpp.

◆ DepthInfoConnect()

void gazebo::GazeboNoisyDepth::DepthInfoConnect ( )
private

Definition at line 186 of file gazebo_noisydepth_plugin.cpp.

◆ DepthInfoDisconnect()

void gazebo::GazeboNoisyDepth::DepthInfoDisconnect ( )
private

Definition at line 190 of file gazebo_noisydepth_plugin.cpp.

◆ FillDepthImage()

void gazebo::GazeboNoisyDepth::FillDepthImage ( const float _src)
private

Definition at line 244 of file gazebo_noisydepth_plugin.cpp.

◆ FillDepthImageHelper()

bool gazebo::GazeboNoisyDepth::FillDepthImageHelper ( const uint32_t  rows_arg,
const uint32_t  cols_arg,
const uint32_t  step_arg,
const float data_arg,
sensor_msgs::Image *  image_msg 
)
private

Definition at line 259 of file gazebo_noisydepth_plugin.cpp.

◆ Load()

void gazebo::GazeboNoisyDepth::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Load the plugin.

Parameters
takein SDF root element

Definition at line 48 of file gazebo_noisydepth_plugin.cpp.

◆ OnNewDepthFrame()

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

Definition at line 194 of file gazebo_noisydepth_plugin.cpp.

◆ OnNewImageFrame()

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

Definition at line 219 of file gazebo_noisydepth_plugin.cpp.

◆ PublishCameraInfo()

void gazebo::GazeboNoisyDepth::PublishCameraInfo ( )
privatevirtual

Definition at line 284 of file gazebo_noisydepth_plugin.cpp.

Member Data Documentation

◆ depth_image_camera_info_pub_

ros::Publisher gazebo::GazeboNoisyDepth::depth_image_camera_info_pub_
private

Definition at line 99 of file gazebo_noisydepth_plugin.h.

◆ depth_image_camera_info_topic_name_

std::string gazebo::GazeboNoisyDepth::depth_image_camera_info_topic_name_
private

Definition at line 105 of file gazebo_noisydepth_plugin.h.

◆ depth_image_connect_count_

int gazebo::GazeboNoisyDepth::depth_image_connect_count_
private

Definition at line 101 of file gazebo_noisydepth_plugin.h.

◆ depth_image_msg_

sensor_msgs::Image gazebo::GazeboNoisyDepth::depth_image_msg_
private

Definition at line 109 of file gazebo_noisydepth_plugin.h.

◆ depth_image_pub_

ros::Publisher gazebo::GazeboNoisyDepth::depth_image_pub_
private

Definition at line 98 of file gazebo_noisydepth_plugin.h.

◆ depth_image_topic_name_

std::string gazebo::GazeboNoisyDepth::depth_image_topic_name_
private

Definition at line 104 of file gazebo_noisydepth_plugin.h.

◆ depth_info_connect_count_

int gazebo::GazeboNoisyDepth::depth_info_connect_count_
private

Definition at line 102 of file gazebo_noisydepth_plugin.h.

◆ depth_sensor_update_time_

common::Time gazebo::GazeboNoisyDepth::depth_sensor_update_time_
private

Definition at line 107 of file gazebo_noisydepth_plugin.h.

◆ last_depth_image_camera_info_update_time_

common::Time gazebo::GazeboNoisyDepth::last_depth_image_camera_info_update_time_
private

Definition at line 108 of file gazebo_noisydepth_plugin.h.

◆ load_connection_

event::ConnectionPtr gazebo::GazeboNoisyDepth::load_connection_
private

Definition at line 95 of file gazebo_noisydepth_plugin.h.

◆ noise_model

std::unique_ptr<DepthNoiseModel> gazebo::GazeboNoisyDepth::noise_model
private

Definition at line 96 of file gazebo_noisydepth_plugin.h.


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


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04