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: Nathan Koenig 00024 * Date: 01 Feb 2007 00025 * SVN: $Id: gazebo_ros_block_laser.hh 6656 2008-06-20 22:52:19Z natepak $ 00026 */ 00027 00028 #ifndef GAZEBO_ROS_BLOCK_LASER_HH 00029 #define GAZEBO_ROS_BLOCK_LASER_HH 00030 00031 // Custom Callback Queue 00032 #include <ros/ros.h> 00033 #include <ros/callback_queue.h> 00034 #include <ros/advertise_options.h> 00035 00036 #include "sdf/interface/Param.hh" 00037 #include "physics/physics.hh" 00038 #include "transport/TransportTypes.hh" 00039 #include "msgs/MessageTypes.hh" 00040 #include "common/Time.hh" 00041 #include "common/Plugin.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/PointCloud.h> 00050 00051 namespace gazebo 00052 { 00053 00054 class GazeboRosBlockLaser : public RayPlugin 00055 { 00058 public: GazeboRosBlockLaser(); 00059 00061 public: ~GazeboRosBlockLaser(); 00062 00065 public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf); 00066 00068 protected: virtual void OnNewLaserScans(); 00069 00071 private: void PutLaserData(common::Time &_updateTime); 00072 00073 private: common::Time last_update_time_; 00074 00076 private: int laser_connect_count_; 00077 private: void LaserConnect(); 00078 private: void LaserDisconnect(); 00079 00080 // Pointer to the model 00081 private: physics::WorldPtr world_; 00083 private: sensors::SensorPtr parent_sensor_; 00084 private: sensors::RaySensorPtr parent_ray_sensor_; 00085 00087 private: ros::NodeHandle* rosnode_; 00088 private: ros::Publisher pub_; 00089 00091 private: sensor_msgs::PointCloud cloud_msg_; 00092 00094 private: std::string topic_name_; 00095 00097 private: std::string frame_name_; 00098 00100 private: double gaussian_noise_; 00101 00103 private: double GaussianKernel(double mu,double sigma); 00104 00106 private: boost::mutex lock; 00107 00109 //private: ParamT<double> *hokuyoMinIntensityP; 00110 private: double hokuyo_min_intensity_; 00111 00113 private: double update_rate_; 00114 00116 private: std::string robot_namespace_; 00117 00118 // Custom Callback Queue 00119 private: ros::CallbackQueue laser_queue_; 00120 private: void LaserQueueThread(); 00121 private: boost::thread callback_laser_queue_thread_; 00122 00123 // subscribe to world stats 00124 private: transport::NodePtr node_; 00125 private: common::Time sim_time_; 00126 public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg); 00127 00128 }; 00129 00130 } 00131 00132 #endif 00133