Go to the documentation of this file.
35 #ifndef GAZEBO_ROS_VELODYNE_LASER_H_
36 #define GAZEBO_ROS_VELODYNE_LASER_H_
43 #include <sdf/Param.hh>
44 #include <gazebo/physics/physics.hh>
45 #include <gazebo/transport/TransportTypes.hh>
46 #include <gazebo/msgs/MessageTypes.hh>
47 #include <gazebo/common/Time.hh>
48 #include <gazebo/common/Plugin.hh>
49 #include <gazebo/sensors/SensorTypes.hh>
50 #include <gazebo/plugins/RayPlugin.hh>
52 #include <boost/bind.hpp>
53 #include <boost/thread.hpp>
54 #include <boost/thread/mutex.hpp>
59 class GazeboRosVelodyneLaser :
public RayPlugin
70 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
86 private: physics::WorldPtr
world_;
115 double U = (double)rand() / (double)RAND_MAX;
116 double V = (double)rand() / (double)RAND_MAX;
117 return sigma * (sqrt(-2.0 * ::log(U)) * cos(2.0 * M_PI * V)) + mu;
121 private: boost::mutex
lock_;
132 private: transport::NodePtr
node_;
GazeboRosVelodyneLaser()
Constructor.
static double gaussianKernel(double mu, double sigma)
Gaussian noise generator.
common::Time last_update_time_
void onStats(const boost::shared_ptr< msgs::WorldStatistics const > &_msg)
void putLaserData(common::Time &_updateTime)
Put laser data to the ROS topic.
int laser_connect_count_
Keep track of number of connections.
std::string frame_name_
frame transform name, should match link name
ros::CallbackQueue laser_queue_
double gaussian_noise_
Gaussian noise.
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
sensors::RaySensorPtr parent_ray_sensor_
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::string robot_namespace_
for setting ROS name space
double max_range_
Maximum range to publish.
sensors::SensorPtr parent_sensor_
The parent sensor.
boost::thread callback_laser_queue_thread_
ros::NodeHandle * rosnode_
pointer to ros node
double min_range_
Minimum range to publish.
~GazeboRosVelodyneLaser()
Destructor.
std::string topic_name_
topic name
virtual void OnNewLaserScans()
Update the controller.