Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef GAZEBO_ROS_VELODYNE_LASER_H_
00036 #define GAZEBO_ROS_VELODYNE_LASER_H_
00037
00038
00039 #include <ros/ros.h>
00040 #include <ros/callback_queue.h>
00041 #include <ros/advertise_options.h>
00042
00043 #include <sdf/Param.hh>
00044 #include <gazebo/physics/physics.hh>
00045 #include <gazebo/transport/TransportTypes.hh>
00046 #include <gazebo/msgs/MessageTypes.hh>
00047
00048 #include <gazebo/common/Time.hh>
00049 #include <gazebo/common/Plugin.hh>
00050 #include <gazebo/sensors/SensorTypes.hh>
00051 #include <gazebo/plugins/RayPlugin.hh>
00052
00053 #include <boost/bind.hpp>
00054 #include <boost/thread.hpp>
00055 #include <boost/thread/mutex.hpp>
00056 #include <boost/thread/lock_guard.hpp>
00057
00058 namespace gazebo
00059 {
00060
00061 class GazeboRosVelodyneLaser : public RayPlugin
00062 {
00065 public: GazeboRosVelodyneLaser();
00066
00068 public: ~GazeboRosVelodyneLaser();
00069
00072 public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00073
00075 private: void ConnectCb();
00076
00078 private: sensors::RaySensorPtr parent_ray_sensor_;
00079
00081 private: ros::NodeHandle* nh_;
00082
00084 private: ros::Publisher pub_;
00085
00087 private: std::string topic_name_;
00088
00090 private: std::string frame_name_;
00091
00093 private: double min_range_;
00094
00096 private: double max_range_;
00097
00099 private: double gaussian_noise_;
00100
00102 private: static double gaussianKernel(double mu, double sigma)
00103 {
00104
00105
00106 double U = (double)rand() / (double)RAND_MAX;
00107 double V = (double)rand() / (double)RAND_MAX;
00108 return sigma * (sqrt(-2.0 * ::log(U)) * cos(2.0 * M_PI * V)) + mu;
00109 }
00110
00112 private: boost::mutex lock_;
00113
00115 private: std::string robot_namespace_;
00116
00117
00118 private: ros::CallbackQueue laser_queue_;
00119 private: void laserQueueThread();
00120 private: boost::thread callback_laser_queue_thread_;
00121
00122
00123 private: gazebo::transport::NodePtr gazebo_node_;
00124 private: gazebo::transport::SubscriberPtr sub_;
00125 private: void OnScan(const ConstLaserScanStampedPtr &_msg);
00126
00127 };
00128
00129 }
00130
00131 #endif
00132