Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
gazebo::GazeboRosDepthCamera Class Reference

#include <gazebo_ros_depth_camera.h>

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

List of all members.

Public Member Functions

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

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.
virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller.
virtual void OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller.
virtual void PublishCameraInfo ()

Protected Attributes

ros::Publisher depth_image_camera_info_pub_

Private Member Functions

void DepthImageConnect ()
void DepthImageDisconnect ()
void DepthInfoConnect ()
void DepthInfoDisconnect ()
void FillDepthImage (const float *_src)
 push depth image data into ros topic
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.
void InfoConnect ()
 Keep track of number of connctions for CameraInfo.
void InfoDisconnect ()
void PointCloudConnect ()
void PointCloudDisconnect ()

Private Attributes

std::string depth_image_camera_info_topic_name_
int depth_image_connect_count_
 Keep track of number of connctions for point clouds.
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
int depth_info_connect_count_
common::Time depth_sensor_update_time_
common::Time last_depth_image_camera_info_update_time_
event::ConnectionPtr load_connection_
int point_cloud_connect_count_
 Keep track of number of connctions for point clouds.
double point_cloud_cutoff_
sensor_msgs::PointCloud2 point_cloud_msg_
 PointCloud2 point cloud message.
ros::Publisher point_cloud_pub_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string point_cloud_topic_name_
 ROS image topic name.

Detailed Description

Definition at line 60 of file gazebo_ros_depth_camera.h.


Constructor & Destructor Documentation

Constructor.

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

Definition at line 45 of file gazebo_ros_depth_camera.cpp.

Destructor.

Definition at line 54 of file gazebo_ros_depth_camera.cpp.


Member Function Documentation

Advertise point cloud and depth image.

Definition at line 112 of file gazebo_ros_depth_camera.cpp.

Definition at line 160 of file gazebo_ros_depth_camera.cpp.

Definition at line 167 of file gazebo_ros_depth_camera.cpp.

Definition at line 174 of file gazebo_ros_depth_camera.cpp.

Definition at line 180 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::FillDepthImage ( const float *  _src) [private]

push depth image data into ros topic

copy from depth to depth image message

Definition at line 354 of file gazebo_ros_depth_camera.cpp.

bool gazebo::GazeboRosDepthCamera::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 463 of file gazebo_ros_depth_camera.cpp.

bool gazebo::GazeboRosDepthCamera::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 376 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::FillPointdCloud ( const float *  _src) [private]

Put camera data to the ROS topic.

copy from depth to point cloud message

Definition at line 329 of file gazebo_ros_depth_camera.cpp.

Keep track of number of connctions for CameraInfo.

Reimplemented from gazebo::GazeboRosCameraUtils.

Reimplemented from gazebo::GazeboRosCameraUtils.

void gazebo::GazeboRosDepthCamera::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
) [virtual]

Load the plugin.

Parameters:
takein SDF root element

Definition at line 60 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::OnNewDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string _format 
) [protected, virtual]

Update the controller.

Definition at line 187 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::OnNewImageFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string _format 
) [protected, virtual]

Update the controller.

Definition at line 296 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::OnNewRGBPointCloud ( const float *  _pcd,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string _format 
) [protected, virtual]

Update the controller.

Definition at line 227 of file gazebo_ros_depth_camera.cpp.

Definition at line 142 of file gazebo_ros_depth_camera.cpp.

Definition at line 150 of file gazebo_ros_depth_camera.cpp.

void gazebo::GazeboRosDepthCamera::PublishCameraInfo ( ) [protected, virtual]

Reimplemented from gazebo::GazeboRosCameraUtils.

Definition at line 501 of file gazebo_ros_depth_camera.cpp.


Member Data Documentation

Definition at line 144 of file gazebo_ros_depth_camera.h.

Definition at line 137 of file gazebo_ros_depth_camera.h.

Keep track of number of connctions for point clouds.

Definition at line 103 of file gazebo_ros_depth_camera.h.

sensor_msgs::Image gazebo::GazeboRosDepthCamera::depth_image_msg_ [private]

Definition at line 122 of file gazebo_ros_depth_camera.h.

Definition at line 118 of file gazebo_ros_depth_camera.h.

image where each pixel contains the depth information

Definition at line 136 of file gazebo_ros_depth_camera.h.

Definition at line 138 of file gazebo_ros_depth_camera.h.

Definition at line 143 of file gazebo_ros_depth_camera.h.

Definition at line 106 of file gazebo_ros_depth_camera.h.

Definition at line 146 of file gazebo_ros_depth_camera.h.

Keep track of number of connctions for point clouds.

Definition at line 98 of file gazebo_ros_depth_camera.h.

Definition at line 124 of file gazebo_ros_depth_camera.h.

sensor_msgs::PointCloud2 gazebo::GazeboRosDepthCamera::point_cloud_msg_ [private]

PointCloud2 point cloud message.

Definition at line 121 of file gazebo_ros_depth_camera.h.

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

Definition at line 117 of file gazebo_ros_depth_camera.h.

ROS image topic name.

Definition at line 127 of file gazebo_ros_depth_camera.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:10