23 #ifndef GAZEBO_ROS_BLOCK_LASER_HH 24 #define GAZEBO_ROS_BLOCK_LASER_HH 31 #include <sdf/Param.hh> 32 #include <gazebo/physics/physics.hh> 33 #include <gazebo/transport/TransportTypes.hh> 34 #include <gazebo/msgs/MessageTypes.hh> 35 #include <gazebo/common/Time.hh> 36 #include <gazebo/common/Plugin.hh> 37 #include <gazebo/sensors/SensorTypes.hh> 38 #include <gazebo/plugins/RayPlugin.hh> 40 #include <boost/bind.hpp> 41 #include <boost/thread.hpp> 42 #include <boost/thread/mutex.hpp> 44 #include <sensor_msgs/PointCloud.h> 60 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
int laser_connect_count_
Keep track of number of connctions.
void PutLaserData(common::Time &_updateTime)
Put laser data to the ROS topic.
double hokuyo_min_intensity_
hack to mimic hokuyo intensity cutoff of 100
ros::NodeHandle * rosnode_
pointer to ros node
boost::thread callback_laser_queue_thread_
ros::CallbackQueue laser_queue_
GazeboRosBlockLaser()
Constructor.
boost::mutex lock
A mutex to lock access to fields that are used in message callbacks.
std::string robot_namespace_
for setting ROS name space
std::string frame_name_
frame transform name, should match link name
std::string topic_name_
topic name
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
~GazeboRosBlockLaser()
Destructor.
sensors::SensorPtr parent_sensor_
The parent sensor.
double gaussian_noise_
Gaussian noise.
sensors::RaySensorPtr parent_ray_sensor_
common::Time last_update_time_
virtual void OnNewLaserScans()
Update the controller.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
double update_rate_
update rate of this sensor
void OnStats(const boost::shared_ptr< msgs::WorldStatistics const > &_msg)
sensor_msgs::PointCloud cloud_msg_
ros message