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_DEPTH_CAMERA_HH
00028 #define GAZEBO_ROS_DEPTH_CAMERA_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.h"
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/GazeboRosCameraConfig.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 GazeboRosDepthCamera : public DepthCameraPlugin, GazeboRosCameraUtils
00068 {
00071 public: GazeboRosDepthCamera();
00072
00074 public: ~GazeboRosDepthCamera();
00075
00078 public: 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 OnNewRGBPointCloud(const float *_pcd,
00087 unsigned int _width, unsigned int _height,
00088 unsigned int _depth, const std::string &_format);
00089
00091 protected: virtual void OnNewImageFrame(const unsigned char *_image,
00092 unsigned int _width, unsigned int _height,
00093 unsigned int _depth, const std::string &_format);
00094
00096 private: void FillPointdCloud(const float *_src);
00097
00099 private: int point_cloud_connect_count_;
00100 private: void PointCloudConnect();
00101 private: void PointCloudDisconnect();
00102
00103 private: bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg,
00104 uint32_t rows_arg, uint32_t cols_arg,
00105 uint32_t step_arg, void* data_arg);
00106
00107 private: bool FillDepthImageHelper( sensor_msgs::Image& image_msg,
00108 uint32_t rows_arg, uint32_t cols_arg,
00109 uint32_t step_arg, void* data_arg);
00110
00112 private: ros::Publisher point_cloud_pub_;
00113 private: ros::Publisher depth_image_pub_;
00114
00116 private: sensor_msgs::PointCloud2 point_cloud_msg_;
00117 private: sensor_msgs::Image depth_image_msg_;
00118
00119 private: double point_cloud_cutoff_;
00120
00122 private: std::string point_cloud_topic_name_;
00123
00124 private: void InfoConnect();
00125 private: void InfoDisconnect();
00126 using GazeboRosCameraUtils::PublishCameraInfo;
00127 private: void PublishCameraInfo();
00128
00130 private: std::string depth_image_topic_name_;
00131 private: std::string depth_image_camera_info_topic_name_;
00132
00133
00134 private: common::Time depth_sensor_update_time_;
00135 protected: ros::Publisher depth_image_camera_info_pub_;
00136 };
00137
00138 }
00139 #endif
00140