Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef GAZEBO_ROS_OPENNI_KINECT_HH
00028 #define GAZEBO_ROS_OPENNI_KINECT_HH
00029
00030
00031 #include <ros/ros.h>
00032 #include <ros/callback_queue.h>
00033 #include <ros/advertise_options.h>
00034
00035 #include <pcl_ros/point_cloud.h>
00036 #include <pcl/point_types.h>
00037
00038
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <sensor_msgs/Image.h>
00041 #include <sensor_msgs/CameraInfo.h>
00042 #include "sensor_msgs/fill_image.h"
00043 #include <std_msgs/Float64.h>
00044 #include "image_transport/image_transport.h"
00045
00046
00047 #include "sdf/interface/Param.hh"
00048 #include "physics/physics.hh"
00049 #include "transport/TransportTypes.hh"
00050 #include "msgs/MessageTypes.hh"
00051 #include "common/Time.hh"
00052 #include "sensors/SensorTypes.hh"
00053 #include "plugins/DepthCameraPlugin.hh"
00054
00055
00056 #include <gazebo_plugins/GazeboRosOpenniKinectConfig.h>
00057 #include <dynamic_reconfigure/server.h>
00058
00059
00060 #include "boost/thread/mutex.hpp"
00061
00062
00063 #include <gazebo_plugins/gazebo_ros_camera_utils.h>
00064
00065 namespace gazebo
00066 {
00067 class GazeboRosOpenniKinect : public DepthCameraPlugin, GazeboRosCameraUtils
00068 {
00071 public: GazeboRosOpenniKinect();
00072
00074 public: ~GazeboRosOpenniKinect();
00075
00078 public: virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00079
00081 protected: virtual void OnNewDepthFrame(const float *_image,
00082 unsigned int _width, unsigned int _height,
00083 unsigned int _depth, const std::string &_format);
00084
00086 protected: virtual void OnNewImageFrame(const unsigned char *_image,
00087 unsigned int _width, unsigned int _height,
00088 unsigned int _depth, const std::string &_format);
00089
00091 private: void FillPointdCloud(const float *_src);
00092
00094 private: void FillDepthImage(const float *_src);
00095
00097 private: int point_cloud_connect_count_;
00098 private: void PointCloudConnect();
00099 private: void PointCloudDisconnect();
00100
00102 private: int depth_image_connect_count_;
00103 private: void DepthImageConnect();
00104 private: void DepthImageDisconnect();
00105
00106 private: bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg,
00107 uint32_t rows_arg, uint32_t cols_arg,
00108 uint32_t step_arg, void* data_arg);
00109
00110 private: bool FillDepthImageHelper( sensor_msgs::Image& image_msg,
00111 uint32_t height, uint32_t width,
00112 uint32_t step, void* data_arg);
00113
00115 private: ros::Publisher point_cloud_pub_;
00116 private: ros::Publisher depth_image_pub_;
00117
00119 private: sensor_msgs::PointCloud2 point_cloud_msg_;
00120 private: sensor_msgs::Image depth_image_msg_;
00121
00122 private: double point_cloud_cutoff_;
00123
00125 private: std::string point_cloud_topic_name_;
00126
00127
00129 private: std::string depth_image_topic_name_;
00130 private: common::Time depth_sensor_update_time_;
00131
00132
00133 private: std::string depth_image_camera_info_topic_name_;
00134 private: int depth_info_connect_count_;
00135 private: void DepthInfoConnect();
00136 private: void DepthInfoDisconnect();
00137 private: common::Time last_depth_image_camera_info_update_time_;
00138 protected: ros::Publisher depth_image_camera_info_pub_;
00139
00140 using GazeboRosCameraUtils::PublishCameraInfo;
00141 protected: virtual void PublishCameraInfo();
00142 };
00143
00144 }
00145 #endif
00146