#include <gazebo_ros_openni_kinect.h>
|  | 
| 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 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  More... 
 | 
|  | 
| void | PointCloudConnect () | 
|  | 
| void | PointCloudDisconnect () | 
|  | 
|  | GazeboRosCameraUtils () | 
|  | Constructor.  More... 
 | 
|  | 
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline) | 
|  | Load the plugin.  More... 
 | 
|  | 
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="") | 
|  | Load the plugin.  More... 
 | 
|  | 
| event::ConnectionPtr | OnLoad (const boost::function< void()> &) | 
|  | 
|  | ~GazeboRosCameraUtils () | 
|  | Destructor.  More... 
 | 
|  | 
| void | CameraQueueThread () | 
|  | 
| virtual bool | CanTriggerCamera () | 
|  | 
| void | ImageConnect () | 
|  | 
| void | ImageDisconnect () | 
|  | 
| void | PublishCameraInfo () | 
|  | 
| void | PublishCameraInfo (common::Time &last_update_time) | 
|  | 
| void | PublishCameraInfo (ros::Publisher camera_info_publisher) | 
|  | Publish CameraInfo to the ROS topic.  More... 
 | 
|  | 
| void | PutCameraData (const unsigned char *_src) | 
|  | Put camera data to the ROS topic.  More... 
 | 
|  | 
| void | PutCameraData (const unsigned char *_src, common::Time &last_update_time) | 
|  | 
| virtual void | TriggerCamera () | 
|  | 
Definition at line 60 of file gazebo_ros_openni_kinect.h.
 
◆ GazeboRosOpenniKinect()
      
        
          | gazebo::GazeboRosOpenniKinect::GazeboRosOpenniKinect | ( |  | ) |  | 
      
 
 
◆ ~GazeboRosOpenniKinect()
      
        
          | gazebo::GazeboRosOpenniKinect::~GazeboRosOpenniKinect | ( |  | ) |  | 
      
 
 
◆ Advertise()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::Advertise | ( |  | ) |  |  | virtual | 
 
 
◆ DepthImageConnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::DepthImageConnect | ( |  | ) |  |  | private | 
 
 
◆ DepthImageDisconnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::DepthImageDisconnect | ( |  | ) |  |  | private | 
 
 
◆ DepthInfoConnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::DepthInfoConnect | ( |  | ) |  |  | private | 
 
 
◆ DepthInfoDisconnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::DepthInfoDisconnect | ( |  | ) |  |  | private | 
 
 
◆ FillDepthImage()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::FillDepthImage | ( | const float * | _src | ) |  |  | private | 
 
 
◆ FillDepthImageHelper()
  
  | 
        
          | bool gazebo::GazeboRosOpenniKinect::FillDepthImageHelper | ( | sensor_msgs::Image & | image_msg, |  
          |  |  | uint32_t | height, |  
          |  |  | uint32_t | width, |  
          |  |  | uint32_t | step, |  
          |  |  | void * | data_arg |  
          |  | ) |  |  |  | private | 
 
 
◆ FillPointCloudHelper()
  
  | 
        
          | 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 | 
 
 
◆ FillPointdCloud()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::FillPointdCloud | ( | const float * | _src | ) |  |  | private | 
 
 
◆ Load()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::Load | ( | sensors::SensorPtr | _parent, |  
          |  |  | sdf::ElementPtr | _sdf |  
          |  | ) |  |  |  | virtual | 
 
 
◆ OnNewDepthFrame()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::OnNewDepthFrame | ( | const float * | _image, |  
          |  |  | unsigned int | _width, |  
          |  |  | unsigned int | _height, |  
          |  |  | unsigned int | _depth, |  
          |  |  | const std::string & | _format |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ OnNewImageFrame()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::OnNewImageFrame | ( | const unsigned char * | _image, |  
          |  |  | unsigned int | _width, |  
          |  |  | unsigned int | _height, |  
          |  |  | unsigned int | _depth, |  
          |  |  | const std::string & | _format |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ PointCloudConnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::PointCloudConnect | ( |  | ) |  |  | private | 
 
 
◆ PointCloudDisconnect()
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::PointCloudDisconnect | ( |  | ) |  |  | private | 
 
 
◆ PublishCameraInfo() [1/4]
  
  | 
        
          | void gazebo::GazeboRosCameraUtils::PublishCameraInfo |  | protected | 
 
 
◆ PublishCameraInfo() [2/4]
  
  | 
        
          | void gazebo::GazeboRosOpenniKinect::PublishCameraInfo | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ PublishCameraInfo() [3/4]
  
  | 
        
          | void gazebo::GazeboRosCameraUtils::PublishCameraInfo |  | protected | 
 
 
◆ PublishCameraInfo() [4/4]
  
  | 
        
          | void gazebo::GazeboRosCameraUtils::PublishCameraInfo |  | protected | 
 
 
◆ depth_image_camera_info_pub_
  
  | 
        
          | ros::Publisher gazebo::GazeboRosOpenniKinect::depth_image_camera_info_pub_ |  | protected | 
 
 
◆ depth_image_camera_info_topic_name_
  
  | 
        
          | std::string gazebo::GazeboRosOpenniKinect::depth_image_camera_info_topic_name_ |  | private | 
 
 
◆ depth_image_connect_count_
  
  | 
        
          | int gazebo::GazeboRosOpenniKinect::depth_image_connect_count_ |  | private | 
 
 
◆ depth_image_msg_
  
  | 
        
          | sensor_msgs::Image gazebo::GazeboRosOpenniKinect::depth_image_msg_ |  | private | 
 
 
◆ depth_image_pub_
◆ depth_image_topic_name_
  
  | 
        
          | std::string gazebo::GazeboRosOpenniKinect::depth_image_topic_name_ |  | private | 
 
 
◆ depth_info_connect_count_
  
  | 
        
          | int gazebo::GazeboRosOpenniKinect::depth_info_connect_count_ |  | private | 
 
 
◆ depth_sensor_update_time_
  
  | 
        
          | common::Time gazebo::GazeboRosOpenniKinect::depth_sensor_update_time_ |  | private | 
 
 
◆ last_depth_image_camera_info_update_time_
  
  | 
        
          | common::Time gazebo::GazeboRosOpenniKinect::last_depth_image_camera_info_update_time_ |  | private | 
 
 
◆ load_connection_
◆ point_cloud_connect_count_
  
  | 
        
          | int gazebo::GazeboRosOpenniKinect::point_cloud_connect_count_ |  | private | 
 
 
◆ point_cloud_cutoff_
  
  | 
        
          | double gazebo::GazeboRosOpenniKinect::point_cloud_cutoff_ |  | private | 
 
 
◆ point_cloud_cutoff_max_
  
  | 
        
          | double gazebo::GazeboRosOpenniKinect::point_cloud_cutoff_max_ |  | private | 
 
 
◆ point_cloud_msg_
  
  | 
        
          | sensor_msgs::PointCloud2 gazebo::GazeboRosOpenniKinect::point_cloud_msg_ |  | private | 
 
 
◆ point_cloud_pub_
◆ point_cloud_topic_name_
  
  | 
        
          | std::string gazebo::GazeboRosOpenniKinect::point_cloud_topic_name_ |  | private | 
 
 
◆ use_depth_image_16UC1_format_
  
  | 
        
          | bool gazebo::GazeboRosOpenniKinect::use_depth_image_16UC1_format_ |  | private | 
 
 
The documentation for this class was generated from the following files: