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 #ifndef GAZEBO_ROS_DEPTH_CAMERA_HH
00024 #define GAZEBO_ROS_DEPTH_CAMERA_HH
00025
00026
00027 #include <ros/ros.h>
00028 #include <ros/callback_queue.h>
00029 #include <ros/advertise_options.h>
00030
00031
00032 #include <sensor_msgs/PointCloud2.h>
00033 #include <sensor_msgs/Image.h>
00034 #include <sensor_msgs/CameraInfo.h>
00035 #include <sensor_msgs/fill_image.h>
00036 #include <std_msgs/Float64.h>
00037 #include <image_transport/image_transport.h>
00038
00039
00040 #include <sdf/Param.hh>
00041 #include <gazebo/physics/physics.hh>
00042 #include <gazebo/transport/TransportTypes.hh>
00043 #include <gazebo/msgs/MessageTypes.hh>
00044 #include <gazebo/common/Time.hh>
00045 #include <gazebo/sensors/SensorTypes.hh>
00046 #include <gazebo/plugins/DepthCameraPlugin.hh>
00047
00048
00049 #include <gazebo_plugins/GazeboRosCameraConfig.h>
00050 #include <dynamic_reconfigure/server.h>
00051
00052
00053 #include <boost/thread/mutex.hpp>
00054
00055
00056 #include <gazebo_plugins/gazebo_ros_camera_utils.h>
00057
00058 namespace gazebo
00059 {
00060 class GazeboRosDepthCamera : public DepthCameraPlugin, GazeboRosCameraUtils
00061 {
00064 public: GazeboRosDepthCamera();
00065
00067 public: ~GazeboRosDepthCamera();
00068
00071 public: virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00072
00074 public: virtual void Advertise();
00075
00077 protected: virtual void OnNewDepthFrame(const float *_image,
00078 unsigned int _width, unsigned int _height,
00079 unsigned int _depth, const std::string &_format);
00080
00082 protected: virtual void OnNewRGBPointCloud(const float *_pcd,
00083 unsigned int _width, unsigned int _height,
00084 unsigned int _depth, const std::string &_format);
00085
00087 protected: virtual void OnNewImageFrame(const unsigned char *_image,
00088 unsigned int _width, unsigned int _height,
00089 unsigned int _depth, const std::string &_format);
00090
00092 private: void FillPointdCloud(const float *_src);
00093
00095 private: void FillDepthImage(const float *_src);
00096
00098 private: int point_cloud_connect_count_;
00099 private: void PointCloudConnect();
00100 private: void PointCloudDisconnect();
00101
00103 private: int depth_image_connect_count_;
00104 private: void DepthImageConnect();
00105 private: void DepthImageDisconnect();
00106 private: common::Time last_depth_image_camera_info_update_time_;
00107
00108 private: bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg,
00109 uint32_t rows_arg, uint32_t cols_arg,
00110 uint32_t step_arg, void* data_arg);
00111
00112 private: bool FillDepthImageHelper( sensor_msgs::Image& image_msg,
00113 uint32_t rows_arg, uint32_t cols_arg,
00114 uint32_t step_arg, void* data_arg);
00115
00117 private: ros::Publisher point_cloud_pub_;
00118 private: ros::Publisher depth_image_pub_;
00119
00121 private: sensor_msgs::PointCloud2 point_cloud_msg_;
00122 private: sensor_msgs::Image depth_image_msg_;
00123
00124 private: double point_cloud_cutoff_;
00125
00127 private: std::string point_cloud_topic_name_;
00128
00129 private: void InfoConnect();
00130 private: void InfoDisconnect();
00131
00132 using GazeboRosCameraUtils::PublishCameraInfo;
00133 protected: virtual void PublishCameraInfo();
00134
00136 private: std::string depth_image_topic_name_;
00137 private: std::string depth_image_camera_info_topic_name_;
00138 private: int depth_info_connect_count_;
00139 private: void DepthInfoConnect();
00140 private: void DepthInfoDisconnect();
00141
00142
00143 private: common::Time depth_sensor_update_time_;
00144 protected: ros::Publisher depth_image_camera_info_pub_;
00145
00146 private: event::ConnectionPtr load_connection_;
00147 };
00148
00149 }
00150 #endif
00151