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: ROS laser controller. 00023 * Author: John Hsu 00024 * Date: 24 Sept 2007 00025 * SVN: $Id$ 00026 */ 00027 00028 #ifndef GAZEBO_ROS_LASER_HH 00029 #define GAZEBO_ROS_LASER_HH 00030 00031 #include <ros/ros.h> 00032 #include <ros/callback_queue.h> 00033 #include <ros/advertise_options.h> 00034 00035 #include "sdf/interface/Param.hh" 00036 #include "physics/physics.hh" 00037 #include "transport/TransportTypes.hh" 00038 #include "msgs/MessageTypes.hh" 00039 #include "common/Time.hh" 00040 #include "common/Plugin.hh" 00041 #include "common/Events.hh" 00042 #include "sensors/SensorTypes.hh" 00043 #include "plugins/RayPlugin.hh" 00044 00045 #include <boost/bind.hpp> 00046 #include <boost/thread.hpp> 00047 #include <boost/thread/mutex.hpp> 00048 00049 #include <sensor_msgs/LaserScan.h> 00050 00051 namespace gazebo 00052 { 00053 class GazeboRosLaser : public RayPlugin 00054 { 00056 public: GazeboRosLaser(); 00057 00059 public: ~GazeboRosLaser(); 00060 00063 public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf); 00064 00066 protected: virtual void OnNewLaserScans(); 00067 00069 private: void PutLaserData(common::Time &_updateTime); 00070 00072 private: int laser_connect_count_; 00073 private: void LaserConnect(); 00074 private: void LaserDisconnect(); 00075 00076 // Pointer to the model 00077 private: physics::WorldPtr world_; 00079 private: sensors::SensorPtr parent_sensor_; 00080 private: sensors::RaySensorPtr parent_ray_sensor_; 00081 00083 private: ros::NodeHandle* rosnode_; 00084 private: ros::Publisher pub_; 00085 00087 private: sensor_msgs::LaserScan laser_msg_; 00088 00090 private: std::string topic_name_; 00091 //private: ParamT<std::string> *topicNameP; 00092 00094 private: std::string frame_name_; 00095 00097 private: double gaussian_noise_; 00098 //private: ParamT<double> *gaussianNoiseP; 00099 00101 private: double GaussianKernel(double mu,double sigma); 00102 00104 private: boost::mutex lock_; 00105 00107 //private: ParamT<double> *hokuyoMinIntensityP; 00108 private: double hokuyo_min_intensity_; 00109 00111 private: double update_rate_; 00112 private: double update_period_; 00113 private: common::Time last_update_time_; 00114 00116 private: std::string robot_namespace_; 00117 00118 private: ros::CallbackQueue laser_queue_; 00119 private: void LaserQueueThread(); 00120 private: boost::thread callback_queue_thread_; 00121 }; 00122 00123 } 00124 00125 #endif 00126