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 topic for generic camera sensor. 00023 * Author: John Hsu 00024 * Date: 24 Sept 2008 00025 * SVN: $Id$ 00026 */ 00027 #ifndef ROS_CAMERA_HH 00028 #define ROS_CAMERA_HH 00029 00030 #include <ros/ros.h> 00031 #define USE_CBQ 00032 #ifdef USE_CBQ 00033 #include <ros/callback_queue.h> 00034 #endif 00035 #include "boost/thread/mutex.hpp" 00036 #include <gazebo/Param.hh> 00037 #include <gazebo/Controller.hh> 00038 00039 // image components 00040 #include "cv_bridge/CvBridge.h" 00041 #include "sensor_msgs/Image.h" 00042 #include "sensor_msgs/CameraInfo.h" 00043 // used by polled_camera 00044 #include "sensor_msgs/RegionOfInterest.h" 00045 00046 // prosilica components 00047 // Stuff in image_common 00048 #include <image_transport/image_transport.h> 00049 #include <polled_camera/publication_server.h> 00050 #include <polled_camera/GetPolledImage.h> 00051 00052 00053 00054 namespace gazebo 00055 { 00056 class MonoCameraSensor; 00057 00060 00139 class GazeboRosProsilica : public Controller 00140 { 00143 public: GazeboRosProsilica(Entity *parent); 00144 00146 public: virtual ~GazeboRosProsilica(); 00147 00150 protected: virtual void LoadChild(XMLConfigNode *node); 00151 00153 protected: virtual void InitChild(); 00154 00156 protected: virtual void UpdateChild(); 00157 00159 protected: virtual void FiniChild(); 00160 00162 private: static void mouse_cb(int event, int x, int y, int flags, void* param) { }; 00163 00165 private: int imageConnectCount; 00166 private: void ImageConnect(); 00167 private: void ImageDisconnect(); 00168 private: int infoConnectCount; 00169 private: void InfoConnect(); 00170 private: void InfoDisconnect(); 00171 00172 private: void PutCameraData(); 00173 private: void PublishCameraInfo(); 00174 00176 private: MonoCameraSensor *myParent; 00177 00179 private: ros::NodeHandle* rosnode_; 00180 00182 private: polled_camera::PublicationServer poll_srv_; // Handles requests in polled mode 00183 00184 private: std::string mode_; 00185 00186 private: ros::Publisher image_pub_; 00187 private: ros::Publisher camera_info_pub_; 00188 00189 /* 00191 private: bool camInfoService(prosilica_camera::CameraInfo::Request &req, 00192 prosilica_camera::CameraInfo::Response &res); 00193 private: bool triggeredGrab(prosilica_camera::PolledImage::Request &req, 00194 prosilica_camera::PolledImage::Response &res); 00195 */ 00196 00197 private: void pollCallback(polled_camera::GetPolledImage::Request& req, 00198 polled_camera::GetPolledImage::Response& rsp, 00199 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info); 00200 00203 private: sensor_msgs::Image imageMsg; 00204 private: sensor_msgs::Image *roiImageMsg; 00205 private: sensor_msgs::CameraInfo cameraInfoMsg; 00206 private: sensor_msgs::CameraInfo *roiCameraInfoMsg; 00207 00208 00210 private: ParamT<std::string> *imageTopicNameP; 00211 private: ParamT<std::string> *cameraInfoTopicNameP; 00212 private: ParamT<std::string> *pollServiceNameP; 00213 private: ParamT<std::string> *frameNameP; 00214 00215 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00216 private: ParamT<double> *CxP; // optical center x 00217 private: ParamT<double> *CyP; // optical center y 00218 private: ParamT<double> *focal_lengthP; // also known as focal length 00219 private: ParamT<double> *hack_baselineP; // also known as focal length 00220 private: ParamT<double> *distortion_k1P; // linear distortion 00221 private: ParamT<double> *distortion_k2P; // quadratic distortion 00222 private: ParamT<double> *distortion_k3P; // cubic distortion 00223 private: ParamT<double> *distortion_t1P; // tangential distortion 00224 private: ParamT<double> *distortion_t2P; // tangential distortion 00225 00227 private: ParamT<std::string> *robotNamespaceP; 00228 private: std::string robotNamespace; 00229 00231 private: std::string imageTopicName; 00232 private: std::string cameraInfoTopicName; 00233 private: std::string pollServiceName; 00234 private: double CxPrime; 00235 private: double Cx; 00236 private: double Cy; 00237 private: double focal_length; 00238 private: double hack_baseline; 00239 private: double distortion_k1; 00240 private: double distortion_k2; 00241 private: double distortion_k3; 00242 private: double distortion_t1; 00243 private: double distortion_t2; 00244 00247 private: std::string frameName; 00248 00250 private: boost::mutex lock; 00251 00253 private: int height, width, depth; 00254 private: std::string type; 00255 private: int skip; 00256 00257 #ifdef USE_CBQ 00258 private: ros::CallbackQueue prosilica_queue_; 00259 private: void ProsilicaQueueThread(); 00260 private: boost::thread prosilica_callback_queue_thread_; 00261 #else 00262 private: void ProsilicaROSThread(); 00263 private: boost::thread ros_spinner_thread_; 00264 #endif 00265 00266 }; 00267 00269 00270 00271 } 00272 #endif 00273