$search
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_CAMERA_HH 00028 #define GAZEBO_ROS_CAMERA_HH 00029 00030 #define USE_CBQ 00031 #ifdef USE_CBQ 00032 #include <ros/callback_queue.h> 00033 #include <ros/advertise_options.h> 00034 #endif 00035 00036 #include <ros/ros.h> 00037 #include "boost/thread/mutex.hpp" 00038 #include <sensor_msgs/Image.h> 00039 #include <sensor_msgs/CameraInfo.h> 00040 #include <std_msgs/Float64.h> 00041 #include <gazebo/Param.hh> 00042 #include <gazebo/Controller.hh> 00043 00044 #include <gazebo_plugins/GazeboRosCameraConfig.h> 00045 #include <dynamic_reconfigure/server.h> 00046 #include <nodelet/loader.h> 00047 00048 #include <pcl_ros/point_cloud.h> 00049 #include <pcl/point_types.h> 00050 #include <Eigen/Core> 00051 00052 #include "image_transport/image_transport.h" 00053 00054 namespace gazebo 00055 { 00056 class MonoCameraSensor; 00057 00060 00112 class GazeboRosCamera : public Controller 00113 { 00116 public: GazeboRosCamera(Entity *parent); 00117 00119 public: virtual ~GazeboRosCamera(); 00120 00123 protected: virtual void LoadChild(XMLConfigNode *node); 00124 00126 protected: virtual void InitChild(); 00127 00129 protected: virtual void UpdateChild(); 00130 00132 protected: virtual void FiniChild(); 00133 00135 private: void PutCameraData(); 00137 private: void PublishCameraInfo(); 00138 00140 private: int imageConnectCount; 00141 private: void ImageConnect(); 00142 private: void ImageDisconnect(); 00143 00145 private: int pointCloudConnectCount; 00146 private: void PointCloudConnect(); 00147 private: void PointCloudDisconnect(); 00148 00150 private: int infoConnectCount; 00151 private: void InfoConnect(); 00152 private: void InfoDisconnect(); 00153 private: void SetHFOV(const std_msgs::Float64::ConstPtr& hfov); 00154 private: void SetUpdateRate(const std_msgs::Float64::ConstPtr& update_rate); 00155 00156 // convert image from gazebo sensor format to desired format 00157 private: void convertImageFormat(unsigned char *dst, const unsigned char *src); 00158 00159 private: bool fillDepthImage(pcl::PointCloud<pcl::PointXYZ>& point_cloud, 00160 uint32_t rows_arg, uint32_t cols_arg, 00161 uint32_t step_arg, void* data_arg); 00162 00164 private: MonoCameraSensor *myParent; 00165 00167 private: ros::NodeHandle* rosnode_; 00168 private: ros::NodeHandle* managernode_; 00169 private: nodelet::Loader* manager_; 00170 private: ros::Publisher point_cloud_pub_,camera_info_pub_; 00171 private: image_transport::Publisher image_pub_; 00172 private: image_transport::ImageTransport* itnode_; 00173 00175 private: sensor_msgs::Image imageMsg; 00176 private: sensor_msgs::CameraInfo cameraInfoMsg; 00177 private: pcl::PointCloud<pcl::PointXYZ> pointCloudMsg; 00178 00180 private: ParamT<std::string> *imageTopicNameP; // deprecated 00181 private: ParamT<std::string> *cameraInfoTopicNameP; // deprecated 00182 private: ParamT<std::string> *pointCloudTopicNameP; 00183 private: ParamT<std::string> *cameraNameP; 00184 private: ParamT<std::string> *frameNameP; 00185 00186 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00187 private: ParamT<double> *CxP; // optical center x 00188 private: ParamT<double> *CyP; // optical center y 00189 private: ParamT<double> *focal_lengthP; // also known as focal length 00190 private: ParamT<double> *hack_baselineP; // also known as focal length 00191 private: ParamT<double> *pointCloudCutoffP; // linear distortion 00192 private: ParamT<double> *distortion_k1P; // linear distortion 00193 private: ParamT<double> *distortion_k2P; // quadratic distortion 00194 private: ParamT<double> *distortion_k3P; // cubic distortion 00195 private: ParamT<double> *distortion_t1P; // tangential distortion 00196 private: ParamT<double> *distortion_t2P; // tangential distortion 00197 00199 private: ParamT<std::string> *robotNamespaceP; 00200 private: std::string robotNamespace; 00201 00203 private: std::string cameraName; 00205 private: std::string imageTopicName; 00207 private: std::string cameraInfoTopicName; 00209 private: std::string pointCloudTopicName; 00212 private: std::string frameName; 00213 00214 private: double CxPrime; 00215 private: double Cx; 00216 private: double Cy; 00217 private: double focal_length; 00218 private: double hack_baseline; 00219 private: double pointCloudCutoff; 00220 private: double distortion_k1; 00221 private: double distortion_k2; 00222 private: double distortion_k3; 00223 private: double distortion_t1; 00224 private: double distortion_t2; 00225 00227 private: boost::mutex lock; 00228 00230 private: int height, width, depth; 00231 private: std::string type; 00232 private: int skip; 00233 00234 private: ros::Subscriber cameraHFOVSubscriber_; 00235 private: ros::Subscriber cameraUpdateRateSubscriber_; 00236 00237 // Time last published, refrain from publish unless new image has been rendered 00238 Time last_point_cloud_pub_time_, last_image_pub_time_, last_camera_info_pub_time_; 00239 00240 // Allow dynamic reconfiguration of camera params 00241 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig> *dyn_srv_; 00242 00243 void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level); 00244 00245 // Name of camera 00246 std::string dynamicReconfigureName; 00247 00248 #ifdef USE_CBQ 00249 private: ros::CallbackQueue camera_queue_; 00250 private: void CameraQueueThread(); 00251 private: boost::thread callback_queue_thread_; 00252 #endif 00253 00254 public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 00255 }; 00256 00258 00259 00260 } 00261 #endif 00262