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 namespace gazebo 00045 { 00046 class MonoCameraSensor; 00047 00050 00102 class GazeboRosCamera : public Controller 00103 { 00106 public: GazeboRosCamera(Entity *parent); 00107 00109 public: virtual ~GazeboRosCamera(); 00110 00113 protected: virtual void LoadChild(XMLConfigNode *node); 00114 00116 protected: virtual void InitChild(); 00117 00119 protected: virtual void UpdateChild(); 00120 00122 protected: virtual void FiniChild(); 00123 00125 private: void PutCameraData(); 00127 private: void PublishCameraInfo(); 00128 00130 private: int imageConnectCount; 00131 private: void ImageConnect(); 00132 private: void ImageDisconnect(); 00133 00135 private: int infoConnectCount; 00136 private: void InfoConnect(); 00137 private: void InfoDisconnect(); 00138 private: void SetHFOV(const std_msgs::Float64::ConstPtr& hfov); 00139 private: void SetUpdateRate(const std_msgs::Float64::ConstPtr& update_rate); 00140 00142 private: MonoCameraSensor *myParent; 00143 00145 private: ros::NodeHandle* rosnode_; 00146 private: ros::Publisher image_pub_,camera_info_pub_; 00147 00149 private: sensor_msgs::Image imageMsg; 00150 private: sensor_msgs::CameraInfo cameraInfoMsg; 00151 00153 private: ParamT<std::string> *imageTopicNameP; 00154 private: ParamT<std::string> *cameraInfoTopicNameP; 00155 private: ParamT<std::string> *frameNameP; 00156 00157 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00158 private: ParamT<double> *CxP; // optical center x 00159 private: ParamT<double> *CyP; // optical center y 00160 private: ParamT<double> *focal_lengthP; // also known as focal length 00161 private: ParamT<double> *hack_baselineP; // also known as focal length 00162 private: ParamT<double> *distortion_k1P; // linear distortion 00163 private: ParamT<double> *distortion_k2P; // quadratic distortion 00164 private: ParamT<double> *distortion_k3P; // cubic distortion 00165 private: ParamT<double> *distortion_t1P; // tangential distortion 00166 private: ParamT<double> *distortion_t2P; // tangential distortion 00167 00169 private: ParamT<std::string> *robotNamespaceP; 00170 private: std::string robotNamespace; 00171 00173 private: std::string imageTopicName; 00175 private: std::string cameraInfoTopicName; 00178 private: std::string frameName; 00179 00180 private: double CxPrime; 00181 private: double Cx; 00182 private: double Cy; 00183 private: double focal_length; 00184 private: double hack_baseline; 00185 private: double distortion_k1; 00186 private: double distortion_k2; 00187 private: double distortion_k3; 00188 private: double distortion_t1; 00189 private: double distortion_t2; 00190 00192 private: boost::mutex lock; 00193 00195 private: int height, width, depth; 00196 private: std::string type; 00197 private: int skip; 00198 00199 private: ros::Subscriber cameraHFOVSubscriber_; 00200 private: ros::Subscriber cameraUpdateRateSubscriber_; 00201 00202 #ifdef USE_CBQ 00203 private: ros::CallbackQueue camera_queue_; 00204 private: void CameraQueueThread(); 00205 private: boost::thread callback_queue_thread_; 00206 #endif 00207 }; 00208 00210 00211 00212 } 00213 #endif 00214