$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 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 #ifdef SIMULATOR_GAZEBO_GAZEBO_ROS_CAMERA_DYNAMIC_RECONFIGURE 00053 #include <gazebo_plugins/GazeboRosCameraConfig.h> 00054 #include <dynamic_reconfigure/server.h> 00055 #endif 00056 00057 namespace gazebo 00058 { 00059 class MonoCameraSensor; 00060 00063 00142 class GazeboRosProsilica : public Controller 00143 { 00146 public: GazeboRosProsilica(Entity *parent); 00147 00149 public: virtual ~GazeboRosProsilica(); 00150 00153 protected: virtual void LoadChild(XMLConfigNode *node); 00154 00156 protected: virtual void InitChild(); 00157 00159 protected: virtual void UpdateChild(); 00160 00162 protected: virtual void FiniChild(); 00163 00165 private: static void mouse_cb(int event, int x, int y, int flags, void* param) { }; 00166 00168 private: int imageConnectCount; 00169 private: void ImageConnect(); 00170 private: void ImageDisconnect(); 00171 private: int infoConnectCount; 00172 private: void InfoConnect(); 00173 private: void InfoDisconnect(); 00174 00175 private: void PutCameraData(); 00176 private: void PublishCameraInfo(); 00177 00179 private: MonoCameraSensor *myParent; 00180 00182 private: ros::NodeHandle* rosnode_; 00183 00185 private: polled_camera::PublicationServer poll_srv_; // Handles requests in polled mode 00186 00187 private: std::string mode_; 00188 00189 private: image_transport::ImageTransport* itnode_; 00190 private: image_transport::Publisher image_pub_; 00191 private: ros::Publisher camera_info_pub_; 00192 00193 /* 00195 private: bool camInfoService(prosilica_camera::CameraInfo::Request &req, 00196 prosilica_camera::CameraInfo::Response &res); 00197 private: bool triggeredGrab(prosilica_camera::PolledImage::Request &req, 00198 prosilica_camera::PolledImage::Response &res); 00199 */ 00200 00201 private: void pollCallback(polled_camera::GetPolledImage::Request& req, 00202 polled_camera::GetPolledImage::Response& rsp, 00203 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info); 00204 00207 private: sensor_msgs::Image imageMsg; 00208 private: sensor_msgs::Image *roiImageMsg; 00209 private: sensor_msgs::CameraInfo cameraInfoMsg; 00210 private: sensor_msgs::CameraInfo *roiCameraInfoMsg; 00211 00212 00214 private: ParamT<std::string> *imageTopicNameP; 00215 private: ParamT<std::string> *cameraInfoTopicNameP; 00216 private: ParamT<std::string> *pollServiceNameP; 00217 private: ParamT<std::string> *frameNameP; 00218 private: ParamT<std::string> *cameraNameP; 00219 00220 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00221 private: ParamT<double> *CxP; // optical center x 00222 private: ParamT<double> *CyP; // optical center y 00223 private: ParamT<double> *focal_lengthP; // also known as focal length 00224 private: ParamT<double> *hack_baselineP; // also known as focal length 00225 private: ParamT<double> *distortion_k1P; // linear distortion 00226 private: ParamT<double> *distortion_k2P; // quadratic distortion 00227 private: ParamT<double> *distortion_k3P; // cubic distortion 00228 private: ParamT<double> *distortion_t1P; // tangential distortion 00229 private: ParamT<double> *distortion_t2P; // tangential distortion 00230 00232 private: ParamT<std::string> *robotNamespaceP; 00233 private: std::string robotNamespace; 00234 00236 private: std::string cameraName; 00237 00239 private: std::string imageTopicName; 00240 private: std::string cameraInfoTopicName; 00241 private: std::string pollServiceName; 00242 private: double CxPrime; 00243 private: double Cx; 00244 private: double Cy; 00245 private: double focal_length; 00246 private: double hack_baseline; 00247 private: double distortion_k1; 00248 private: double distortion_k2; 00249 private: double distortion_k3; 00250 private: double distortion_t1; 00251 private: double distortion_t2; 00252 00255 private: std::string frameName; 00256 00258 private: boost::mutex lock; 00259 00261 private: int height, width, depth; 00262 private: std::string type; 00263 private: int skip; 00264 00265 #ifdef SIMULATOR_GAZEBO_GAZEBO_ROS_CAMERA_DYNAMIC_RECONFIGURE 00266 // Allow dynamic reconfiguration of camera params 00267 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig> *dyn_srv_; 00268 00269 void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level); 00270 00271 // Name of camera 00272 std::string dynamicReconfigureName; 00273 #endif 00274 00275 #ifdef USE_CBQ 00276 private: ros::CallbackQueue prosilica_queue_; 00277 private: void ProsilicaQueueThread(); 00278 private: boost::thread prosilica_callback_queue_thread_; 00279 #else 00280 private: void ProsilicaROSThread(); 00281 private: boost::thread ros_spinner_thread_; 00282 #endif 00283 00284 }; 00285 00287 00288 00289 } 00290 #endif 00291