gazebo_ros_depth_camera.h
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /*
00022  * Desc: A dynamic controller plugin that publishes ROS image_raw camera_info topic for generic camera sensor.
00023  * Author: John Hsu
00024  * Date: 24 Sept 2008
00025  * SVN: $Id$
00026  */
00027 #ifndef GAZEBO_ROS_DEPTH_CAMERA_HH
00028 #define GAZEBO_ROS_DEPTH_CAMERA_HH
00029 
00030 // ros stuff
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 // ros messages stuff
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 // gazebo stuff
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 // dynamic reconfigure stuff
00056 #include <gazebo_plugins/GazeboRosCameraConfig.h>
00057 #include <dynamic_reconfigure/server.h>
00058 
00059 // boost stuff
00060 #include "boost/thread/mutex.hpp"
00061 
00062 // camera stuff
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: 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 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: void FillDepthImage(const float *_src);
00100 
00102     private: int point_cloud_connect_count_;
00103     private: void PointCloudConnect();
00104     private: void PointCloudDisconnect();
00105 
00107     private: int depth_image_connect_count_;
00108     private: void DepthImageConnect();
00109     private: void DepthImageDisconnect();
00110     private: common::Time last_depth_image_camera_info_update_time_;
00111 
00112     private: bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg,
00113                                   uint32_t rows_arg, uint32_t cols_arg,
00114                                   uint32_t step_arg, void* data_arg);
00115 
00116     private: bool FillDepthImageHelper( sensor_msgs::Image& image_msg,
00117                                   uint32_t rows_arg, uint32_t cols_arg,
00118                                   uint32_t step_arg, void* data_arg);
00119 
00121     private: ros::Publisher point_cloud_pub_;
00122     private: ros::Publisher depth_image_pub_;
00123 
00125     private: sensor_msgs::PointCloud2 point_cloud_msg_;
00126     private: sensor_msgs::Image depth_image_msg_;
00127 
00128     private: double point_cloud_cutoff_;
00129 
00131     private: std::string point_cloud_topic_name_;
00132 
00133     private: void InfoConnect();
00134     private: void InfoDisconnect();
00135 
00136     using GazeboRosCameraUtils::PublishCameraInfo;
00137     protected: virtual void PublishCameraInfo();
00138 
00140     private: std::string depth_image_topic_name_;
00141     private: std::string depth_image_camera_info_topic_name_;
00142     private: int depth_info_connect_count_;
00143     private: void DepthInfoConnect();
00144     private: void DepthInfoDisconnect();
00145 
00146     // overload with our own
00147     private: common::Time depth_sensor_update_time_;
00148     protected: ros::Publisher depth_image_camera_info_pub_;
00149   };
00150 
00151 }
00152 #endif
00153 


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 12:15:44