#include <gazebo_ros_openni_kinect.h>

Public Member Functions | |
| GazeboRosOpenniKinect () | |
| Constructor. | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. | |
| ~GazeboRosOpenniKinect () | |
| 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. | |
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 height, uint32_t width, uint32_t step, 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) |
| push point cloud data into ros topic | |
| void | PointCloudConnect () |
| void | PointCloudDisconnect () |
| void | PublishCameraInfo () |
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 data | |
| int | depth_info_connect_count_ |
| common::Time | depth_sensor_update_time_ |
| common::Time | last_depth_image_camera_info_update_time_ |
| int | point_cloud_connect_count_ |
| Keep track of number of connctions for point clouds. | |
| double | point_cloud_cutoff_ |
| sensor_msgs::PointCloud2 | point_cloud_msg_ |
| PCL 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. | |
Definition at line 67 of file gazebo_ros_openni_kinect.h.
Constructor.
| parent | The parent entity, must be a Model or a Sensor |
Definition at line 52 of file gazebo_ros_openni_kinect.cpp.
Destructor.
Definition at line 61 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::DepthImageConnect | ( | ) | [private] |
Definition at line 153 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::DepthImageDisconnect | ( | ) | [private] |
Definition at line 160 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::DepthInfoConnect | ( | ) | [private] |
Definition at line 167 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::DepthInfoDisconnect | ( | ) | [private] |
Definition at line 173 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::FillDepthImage | ( | const float * | _src | ) | [private] |
push depth image data into ros topic
copy from depth to depth image message
Definition at line 269 of file gazebo_ros_openni_kinect.cpp.
| bool gazebo::GazeboRosOpenniKinect::FillDepthImageHelper | ( | sensor_msgs::Image & | image_msg, |
| uint32_t | height, | ||
| uint32_t | width, | ||
| uint32_t | step, | ||
| void * | data_arg | ||
| ) | [private] |
Definition at line 373 of file gazebo_ros_openni_kinect.cpp.
| bool gazebo::GazeboRosOpenniKinect::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 291 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::FillPointdCloud | ( | const float * | _src | ) | [private] |
push point cloud data into ros topic
copy from depth to point cloud message
Definition at line 244 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| take | in SDF root element |
Reimplemented from gazebo::GazeboRosCameraUtils.
Definition at line 67 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::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 180 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::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 213 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::PointCloudConnect | ( | ) | [private] |
Definition at line 135 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::PointCloudDisconnect | ( | ) | [private] |
Definition at line 143 of file gazebo_ros_openni_kinect.cpp.
| void gazebo::GazeboRosOpenniKinect::PublishCameraInfo | ( | ) | [private] |
Reimplemented from gazebo::GazeboRosCameraUtils.
Definition at line 414 of file gazebo_ros_openni_kinect.cpp.
Definition at line 137 of file gazebo_ros_openni_kinect.h.
std::string gazebo::GazeboRosOpenniKinect::depth_image_camera_info_topic_name_ [private] |
Definition at line 132 of file gazebo_ros_openni_kinect.h.
Keep track of number of connctions for point clouds.
Definition at line 101 of file gazebo_ros_openni_kinect.h.
sensor_msgs::Image gazebo::GazeboRosOpenniKinect::depth_image_msg_ [private] |
Definition at line 119 of file gazebo_ros_openni_kinect.h.
Definition at line 115 of file gazebo_ros_openni_kinect.h.
std::string gazebo::GazeboRosOpenniKinect::depth_image_topic_name_ [private] |
image where each pixel contains the depth data
Definition at line 128 of file gazebo_ros_openni_kinect.h.
int gazebo::GazeboRosOpenniKinect::depth_info_connect_count_ [private] |
Definition at line 133 of file gazebo_ros_openni_kinect.h.
common::Time gazebo::GazeboRosOpenniKinect::depth_sensor_update_time_ [private] |
Definition at line 129 of file gazebo_ros_openni_kinect.h.
common::Time gazebo::GazeboRosOpenniKinect::last_depth_image_camera_info_update_time_ [private] |
Definition at line 136 of file gazebo_ros_openni_kinect.h.
Keep track of number of connctions for point clouds.
Definition at line 96 of file gazebo_ros_openni_kinect.h.
double gazebo::GazeboRosOpenniKinect::point_cloud_cutoff_ [private] |
Definition at line 121 of file gazebo_ros_openni_kinect.h.
sensor_msgs::PointCloud2 gazebo::GazeboRosOpenniKinect::point_cloud_msg_ [private] |
PCL point cloud message.
Definition at line 118 of file gazebo_ros_openni_kinect.h.
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 114 of file gazebo_ros_openni_kinect.h.
std::string gazebo::GazeboRosOpenniKinect::point_cloud_topic_name_ [private] |
ROS image topic name.
Definition at line 124 of file gazebo_ros_openni_kinect.h.