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_UTILS_HH 00028 #define GAZEBO_ROS_CAMERA_UTILS_HH 00029 00030 // ros stuff 00031 #include <ros/ros.h> 00032 #include <ros/callback_queue.h> 00033 #include <ros/advertise_options.h> 00034 00035 // ros messages stuff 00036 #include <sensor_msgs/PointCloud.h> 00037 #include <sensor_msgs/Image.h> 00038 #include <sensor_msgs/CameraInfo.h> 00039 #include <std_msgs/Float64.h> 00040 #include "image_transport/image_transport.h" 00041 00042 // gazebo stuff 00043 #include "sdf/interface/Param.hh" 00044 #include "physics/physics.hh" 00045 #include "transport/TransportTypes.hh" 00046 #include "msgs/MessageTypes.hh" 00047 #include "common/Time.hh" 00048 #include "sensors/SensorTypes.hh" 00049 #include "plugins/CameraPlugin.hh" 00050 00051 00052 // dynamic reconfigure stuff 00053 #include <gazebo_plugins/GazeboRosCameraConfig.h> 00054 #include <dynamic_reconfigure/server.h> 00055 00056 // boost stuff 00057 #include <boost/thread.hpp> 00058 #include <boost/thread/mutex.hpp> 00059 00060 00061 namespace gazebo 00062 { 00063 00064 class GazeboRosCameraUtils //: public CameraPlugin 00065 { 00068 public: GazeboRosCameraUtils(); 00069 00071 public: ~GazeboRosCameraUtils(); 00072 00075 public: virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf); 00076 00077 private: void Init(); 00078 00080 protected: void PutCameraData(const unsigned char *_src); 00081 protected: void PutCameraData(const unsigned char *_src, common::Time &last_update_time); 00082 00084 protected: int image_connect_count_; 00085 protected: void ImageConnect(); 00086 protected: void ImageDisconnect(); 00087 00089 private: void SetHFOV(const std_msgs::Float64::ConstPtr& hfov); 00090 private: void SetUpdateRate(const std_msgs::Float64::ConstPtr& update_rate); 00091 00093 protected: ros::NodeHandle* rosnode_; 00094 protected: image_transport::Publisher image_pub_; 00095 private: image_transport::ImageTransport* itnode_; 00096 00098 protected: sensor_msgs::Image image_msg_; 00099 00101 private: std::string robot_namespace_; 00102 00104 private: std::string camera_name_; 00105 00107 protected: std::string image_topic_name_; 00108 00110 protected: virtual void PublishCameraInfo(ros::Publisher &camera_info_publisher); 00111 protected: virtual void PublishCameraInfo(common::Time &last_update_time); 00112 protected: virtual void PublishCameraInfo(); 00114 protected: int info_connect_count_; 00115 private: void InfoConnect(); 00116 private: void InfoDisconnect(); 00118 protected: ros::Publisher camera_info_pub_; 00119 protected: std::string camera_info_topic_name_; 00120 protected: common::Time last_info_update_time_; 00121 00124 protected: std::string frame_name_; 00126 protected: double update_rate_; 00127 protected: double update_period_; 00128 protected: common::Time last_update_time_; 00129 00130 protected: double cx_prime_; 00131 protected: double cx_; 00132 protected: double cy_; 00133 protected: double focal_length_; 00134 protected: double hack_baseline_; 00135 protected: double distortion_k1_; 00136 protected: double distortion_k2_; 00137 protected: double distortion_k3_; 00138 protected: double distortion_t1_; 00139 protected: double distortion_t2_; 00140 00142 protected: boost::mutex lock_; 00143 00145 protected: std::string type_; 00146 protected: int skip_; 00147 00148 private: ros::Subscriber cameraHFOVSubscriber_; 00149 private: ros::Subscriber cameraUpdateRateSubscriber_; 00150 00151 // Time last published, refrain from publish unless new image has been rendered 00152 // Allow dynamic reconfiguration of camera params 00153 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig> *dyn_srv_; 00154 00155 void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level); 00156 00157 protected: ros::CallbackQueue camera_queue_; 00158 protected: void CameraQueueThread(); 00159 protected: boost::thread callback_queue_thread_; 00160 00161 00162 // copied from CameraPlugin 00163 protected: unsigned int width_, height_, depth_; 00164 protected: std::string format_; 00165 00166 protected: sensors::SensorPtr parentSensor_; 00167 protected: rendering::CameraPtr camera_; 00168 00169 // Pointer to the world 00170 protected: physics::WorldPtr world_; 00171 00172 private: event::ConnectionPtr newFrameConnection_; 00173 00174 protected: common::Time sensor_update_time_; 00175 00176 // maintain for one more release for backwards compatibility with pr2_gazebo_plugins 00177 protected: int imageConnectCount; 00178 protected: int infoConnectCount; 00179 protected: physics::WorldPtr world; 00180 }; 00181 00182 } 00183 #endif 00184