35 #ifndef GAZEBO_ROS_VELODYNE_LASER_H_ 36 #define GAZEBO_ROS_VELODYNE_LASER_H_ 39 #ifndef GAZEBO_GPU_RAY 40 #define GAZEBO_GPU_RAY 0 48 #include <sdf/Param.hh> 49 #include <gazebo/physics/physics.hh> 50 #include <gazebo/transport/TransportTypes.hh> 51 #include <gazebo/msgs/MessageTypes.hh> 53 #include <gazebo/common/Time.hh> 54 #include <gazebo/common/Plugin.hh> 55 #include <gazebo/sensors/SensorTypes.hh> 57 #include <gazebo/plugins/GpuRayPlugin.hh> 59 #include <gazebo/plugins/RayPlugin.hh> 62 #include <boost/algorithm/string/trim.hpp> 63 #include <boost/bind.hpp> 64 #include <boost/thread.hpp> 65 #include <boost/thread/mutex.hpp> 66 #include <boost/thread/lock_guard.hpp> 69 #define GazeboRosVelodyneLaser GazeboRosVelodyneGpuLaser 70 #define RayPlugin GpuRayPlugin 71 #define RaySensorPtr GpuRaySensorPtr 88 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
125 double U = (double)rand() / (double)RAND_MAX;
126 double V = (double)rand() / (double)RAND_MAX;
127 return sigma * (sqrt(-2.0 * ::log(U)) * cos(2.0 * M_PI * V)) + mu;
143 private: gazebo::transport::SubscriberPtr
sub_;
144 private:
void OnScan(
const ConstLaserScanStampedPtr &_msg);
void OnScan(const ConstLaserScanStampedPtr &_msg)
ros::NodeHandle * nh_
Pointer to ROS node.
std::string topic_name_
topic name
sensors::RaySensorPtr parent_ray_sensor_
The parent ray sensor.
GazeboRosVelodyneLaser()
Constructor.
gazebo::transport::NodePtr gazebo_node_
static double gaussianKernel(double mu, double sigma)
Gaussian noise generator.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
void ConnectCb()
Subscribe on-demand.
ros::Publisher pub_
ROS publisher.
double gaussian_noise_
Gaussian noise.
boost::thread callback_laser_queue_thread_
gazebo::transport::SubscriberPtr sub_
double min_range_
Minimum range to publish.
~GazeboRosVelodyneLaser()
Destructor.
ros::CallbackQueue laser_queue_
std::string robot_namespace_
For setting ROS name space.
double max_range_
Maximum range to publish.
std::string frame_name_
frame transform name, should match link name
double min_intensity_
the intensity beneath which points will be filtered
boost::mutex lock_
A mutex to lock access.