#include <gazebo_noisydepth_plugin.h>
Public Member Functions | |
virtual void | Advertise () |
Advertise depth image. | |
GazeboNoisyDepth () | |
virtual void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
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 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< DepthNoiseModel > | noise_model |
Definition at line 59 of file gazebo_noisydepth_plugin.h.
Definition at line 40 of file gazebo_noisydepth_plugin.cpp.
Definition at line 46 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::Advertise | ( | ) | [virtual] |
Advertise depth image.
Definition at line 151 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::DepthImageConnect | ( | ) | [private] |
Definition at line 171 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::DepthImageDisconnect | ( | ) | [private] |
Definition at line 176 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::DepthInfoConnect | ( | ) | [private] |
Definition at line 180 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::DepthInfoDisconnect | ( | ) | [private] |
Definition at line 184 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::FillDepthImage | ( | const float * | _src | ) | [private] |
Definition at line 238 of file gazebo_noisydepth_plugin.cpp.
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 253 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [virtual] |
Load the plugin.
take | in SDF root element |
Definition at line 48 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::OnNewDepthFrame | ( | const float * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [virtual] |
Definition at line 188 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::OnNewImageFrame | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Definition at line 213 of file gazebo_noisydepth_plugin.cpp.
void gazebo::GazeboNoisyDepth::PublishCameraInfo | ( | ) | [private, virtual] |
Reimplemented from gazebo::GazeboRosCameraUtils.
Definition at line 278 of file gazebo_noisydepth_plugin.cpp.
Definition at line 99 of file gazebo_noisydepth_plugin.h.
Definition at line 105 of file gazebo_noisydepth_plugin.h.
Definition at line 101 of file gazebo_noisydepth_plugin.h.
sensor_msgs::Image gazebo::GazeboNoisyDepth::depth_image_msg_ [private] |
Definition at line 109 of file gazebo_noisydepth_plugin.h.
Definition at line 98 of file gazebo_noisydepth_plugin.h.
Definition at line 104 of file gazebo_noisydepth_plugin.h.
Definition at line 102 of file gazebo_noisydepth_plugin.h.
common::Time gazebo::GazeboNoisyDepth::depth_sensor_update_time_ [private] |
Definition at line 107 of file gazebo_noisydepth_plugin.h.
common::Time gazebo::GazeboNoisyDepth::last_depth_image_camera_info_update_time_ [private] |
Definition at line 108 of file gazebo_noisydepth_plugin.h.
Definition at line 95 of file gazebo_noisydepth_plugin.h.
std::unique_ptr<DepthNoiseModel> gazebo::GazeboNoisyDepth::noise_model [private] |
Definition at line 96 of file gazebo_noisydepth_plugin.h.