$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_STEREO_CAMERA_HH 00028 #define GAZEBO_ROS_STEREO_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 <gazebo/Param.hh> 00041 #include <gazebo/Controller.hh> 00042 #include <gazebo/StereoCameraSensor.hh> 00043 00044 #include <OgrePrerequisites.h> 00045 #include <OgreTexture.h> 00046 #include <OgreMaterial.h> 00047 #include <OgreImageCodec.h> 00048 #include <Ogre.h> 00049 #include <OgreRenderTargetListener.h> 00050 00051 #include <sensor_msgs/PointCloud.h> 00052 00053 namespace gazebo 00054 { 00055 class MonoCameraSensor; 00056 00059 00113 class GazeboRosStereoCamera : public Controller 00114 { 00117 public: GazeboRosStereoCamera(Entity *parent); 00118 00120 public: virtual ~GazeboRosStereoCamera(); 00121 00124 protected: virtual void LoadChild(XMLConfigNode *node); 00125 00127 protected: virtual void InitChild(); 00128 00130 protected: virtual void UpdateChild(); 00131 00133 protected: virtual void FiniChild(); 00134 00136 private: void PutCameraData(); 00138 private: void PublishCameraInfo(); 00139 00141 public: const float *GetDepthData(unsigned int i=0); 00142 00144 private: int imageConnectCount; 00145 private: void ImageConnect(); 00146 private: void ImageDisconnect(); 00147 00149 private: int pointCloudConnectCount; 00150 private: void PointCloudConnect(); 00151 private: void PointCloudDisconnect(); 00152 00154 private: int infoConnectCount; 00155 private: void InfoConnect(); 00156 private: void InfoDisconnect(); 00157 00159 00163 00165 private: StereoCameraSensor *myParent; 00166 00168 private: ros::NodeHandle* rosnode_; 00169 private: ros::Publisher point_cloud_pub_, image_pub_,camera_info_pub_; 00170 00171 00173 private: sensor_msgs::Image imageMsg; 00174 private: sensor_msgs::CameraInfo cameraInfoMsg; 00175 00177 private: ParamT<std::string> *imageTopicNameP; 00178 private: ParamT<std::string> *pointCloudTopicNameP; 00179 private: ParamT<std::string> *cameraInfoTopicNameP; 00180 private: ParamT<std::string> *frameNameP; 00181 00182 00183 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00184 private: ParamT<double> *CxP; // optical center x 00185 private: ParamT<double> *CyP; // optical center y 00186 private: ParamT<double> *focal_lengthP; // also known as focal length 00187 private: ParamT<double> *hack_baselineP; // also known as focal length 00188 private: ParamT<double> *distortion_k1P; // linear distortion 00189 private: ParamT<double> *distortion_k2P; // quadratic distortion 00190 private: ParamT<double> *distortion_k3P; // cubic distortion 00191 private: ParamT<double> *distortion_t1P; // tangential distortion 00192 private: ParamT<double> *distortion_t2P; // tangential distortion 00193 00195 private: ParamT<std::string> *robotNamespaceP; 00196 private: std::string robotNamespace; 00197 00199 private: std::string imageTopicName; 00201 private: std::string pointCloudTopicName; 00203 private: std::string cameraInfoTopicName; 00206 private: std::string frameName; 00207 00209 bool fillDepthImage(sensor_msgs::PointCloud& point_cloud, 00210 uint32_t rows_arg, 00211 uint32_t cols_arg, 00212 uint32_t step_arg, 00213 void* data_arg); 00214 00215 private: double CxPrime; 00216 private: double Cx; 00217 private: double Cy; 00218 private: double focal_length; 00219 private: double hack_baseline; 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 00235 private: sensor_msgs::PointCloud pointCloudMsg; 00236 00237 #ifdef USE_CBQ 00238 private: ros::CallbackQueue camera_queue_; 00239 private: void CameraQueueThread(); 00240 private: boost::thread callback_queue_thread_; 00241 #endif 00242 }; 00243 00245 00246 00247 } 00248 #endif 00249