$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_OPENNI_KINECT_HH 00028 #define GAZEBO_ROS_OPENNI_KINECT_HH 00029 00030 #include <ros/callback_queue.h> 00031 #include <ros/advertise_options.h> 00032 00033 #include <ros/ros.h> 00034 #include "boost/thread/mutex.hpp" 00035 #include <sensor_msgs/Image.h> 00036 #include <sensor_msgs/CameraInfo.h> 00037 #include <std_msgs/Float64.h> 00038 #include <gazebo/Param.hh> 00039 #include <gazebo/Controller.hh> 00040 00041 #include <gazebo_plugins/GazeboRosOpenniKinectConfig.h> 00042 #include <dynamic_reconfigure/server.h> 00043 #include <nodelet/loader.h> 00044 00045 #include <pcl_ros/point_cloud.h> 00046 #include <pcl/point_types.h> 00047 00048 #include "image_transport/image_transport.h" 00049 00050 namespace gazebo 00051 { 00052 class MonoCameraSensor; 00053 00056 00108 class GazeboRosOpenniKinect : public Controller 00109 { 00112 public: GazeboRosOpenniKinect(Entity *parent); 00113 00115 public: virtual ~GazeboRosOpenniKinect(); 00116 00119 protected: virtual void LoadChild(XMLConfigNode *node); 00120 00122 protected: virtual void InitChild(); 00123 00125 protected: virtual void UpdateChild(); 00126 00128 protected: virtual void FiniChild(); 00129 00131 private: void PutCameraData(); 00133 private: void PublishCameraInfo(ros::Publisher camera_info_publisher); 00134 00136 private: int imageConnectCount; 00137 private: void ImageConnect(); 00138 private: void ImageDisconnect(); 00139 00141 private: int pointCloudConnectCount; 00142 private: void PointCloudConnect(); 00143 private: void PointCloudDisconnect(); 00144 00146 private: int depthImageConnectCount; 00147 private: void DepthImageConnect(); 00148 private: void DepthImageDisconnect(); 00149 00151 private: int infoConnectCount; 00152 private: void InfoConnect(); 00153 private: void InfoDisconnect(); 00154 private: void SetHFOV(const std_msgs::Float64::ConstPtr& hfov); 00155 private: void SetUpdateRate(const std_msgs::Float64::ConstPtr& update_rate); 00156 00157 // convert image from gazebo sensor format to desired format 00158 private: void convertImageFormat(unsigned char *dst, const unsigned char *src); 00159 00160 private: bool FillPointCloudHelper( pcl::PointCloud<pcl::PointXYZ>& point_cloud, 00161 uint32_t rows_arg, uint32_t cols_arg, 00162 uint32_t step_arg, void* data_arg); 00163 00164 private: bool FillDepthImageHelper( sensor_msgs::Image& image_msg, 00165 uint32_t height, uint32_t width, 00166 uint32_t step, void* data_arg); 00167 00169 private: MonoCameraSensor *myParent; 00170 00172 private: ros::NodeHandle* rosnode_; 00173 private: ros::NodeHandle* managernode_; 00174 private: nodelet::Loader* manager_; 00175 private: ros::Publisher point_cloud_pub_,camera_info_pub_; 00176 private: ros::Publisher depth_image_pub_; 00177 private: image_transport::Publisher image_pub_; 00178 private: image_transport::ImageTransport* itnode_; 00179 00180 private: int depthInfoConnectCount; 00181 private: void DepthInfoConnect(); 00182 private: void DepthInfoDisconnect(); 00183 protected: ros::Publisher depth_image_camera_info_pub_; 00184 00186 private: sensor_msgs::Image imageMsg; 00187 private: pcl::PointCloud<pcl::PointXYZ> pointCloudMsg; 00188 00190 private: sensor_msgs::Image depth_image_msg_; 00191 00193 private: ParamT<std::string> *imageTopicNameP; // deprecated 00194 private: ParamT<std::string> *cameraInfoTopicNameP; // deprecated 00195 private: ParamT<std::string> *depthImageCameraInfoTopicNameP; // deprecated 00196 private: ParamT<std::string> *pointCloudTopicNameP; 00197 private: ParamT<std::string> *depthImageTopicNameP; 00198 private: ParamT<std::string> *cameraNameP; 00199 private: ParamT<std::string> *frameNameP; 00200 private: std::string depthImageTopicName; 00201 private: std::string depthImageCameraInfoTopicName; 00202 00203 private: ParamT<double> *CxPrimeP; // rectified optical center x, for sim, CxPrime == Cx 00204 private: ParamT<double> *CxP; // optical center x 00205 private: ParamT<double> *CyP; // optical center y 00206 private: ParamT<double> *focal_lengthP; // also known as focal length 00207 private: ParamT<double> *hack_baselineP; // also known as focal length 00208 private: ParamT<double> *pointCloudCutoffP; // linear distortion 00209 private: ParamT<double> *distortion_k1P; // linear distortion 00210 private: ParamT<double> *distortion_k2P; // quadratic distortion 00211 private: ParamT<double> *distortion_k3P; // cubic distortion 00212 private: ParamT<double> *distortion_t1P; // tangential distortion 00213 private: ParamT<double> *distortion_t2P; // tangential distortion 00214 00216 private: ParamT<std::string> *robotNamespaceP; 00217 private: std::string robotNamespace; 00218 00220 private: std::string cameraName; 00222 private: std::string imageTopicName; 00224 private: std::string cameraInfoTopicName; 00226 private: std::string pointCloudTopicName; 00229 private: std::string frameName; 00230 00231 private: double CxPrime; 00232 private: double Cx; 00233 private: double Cy; 00234 private: double focal_length; 00235 private: double hack_baseline; 00236 private: double pointCloudCutoff; 00237 private: double distortion_k1; 00238 private: double distortion_k2; 00239 private: double distortion_k3; 00240 private: double distortion_t1; 00241 private: double distortion_t2; 00242 00244 private: boost::mutex lock; 00245 00247 private: int height, width, depth; 00248 private: std::string type; 00249 private: int skip; 00250 00251 private: ros::Subscriber cameraHFOVSubscriber_; 00252 private: ros::Subscriber cameraUpdateRateSubscriber_; 00253 00254 // Time last published, refrain from publish unless new image has been rendered 00255 Time last_point_cloud_pub_time_, last_image_pub_time_, last_camera_info_pub_time_; 00256 00257 // Allow dynamic reconfiguration of camera params 00258 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosOpenniKinectConfig> *dyn_srv_; 00259 00260 void configCallback(gazebo_plugins::GazeboRosOpenniKinectConfig &config, uint32_t level); 00261 00262 // Name of camera 00263 std::string dynamicReconfigureName; 00264 00265 private: ros::CallbackQueue camera_queue_; 00266 private: void CameraQueueThread(); 00267 private: boost::thread callback_queue_thread_; 00268 00269 public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 00270 }; 00271 00273 00274 00275 } 00276 #endif 00277