37 #ifndef GAZEBO_ROS_RANGE_H 38 #define GAZEBO_ROS_RANGE_H 43 #include <boost/bind.hpp> 44 #include <boost/thread.hpp> 45 #include <boost/thread/mutex.hpp> 50 #include <sensor_msgs/Range.h> 52 #include <gazebo/physics/physics.hh> 53 #include <gazebo/transport/TransportTypes.hh> 54 #include <gazebo/msgs/MessageTypes.hh> 55 #include <gazebo/common/Time.hh> 56 #include <gazebo/common/Plugin.hh> 57 #include <gazebo/common/Events.hh> 58 #include <gazebo/sensors/SensorTypes.hh> 59 #include <gazebo/plugins/RayPlugin.hh> 61 #include <sdf/Param.hh> 77 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
139 private: sdf::ElementPtr
sdf;
145 #endif // GAZEBO_ROS_RANGE_H
std::string robot_namespace_
for setting ROS name space
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
sensor_msgs::Range range_msg_
ros message
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
ros::NodeHandle * rosnode_
pointer to ros node
~GazeboRosRange()
Destructor.
double update_rate_
update rate of this sensor
GazeboRosRange()
Constructor.
sensors::RaySensorPtr parent_ray_sensor_
std::string radiation_
radiation type : ultrasound or infrared
double hokuyo_min_intensity_
hack to mimic hokuyo intensity cutoff of 100
std::string frame_name_
frame transform name, should match link name
int range_connect_count_
Keep track of number of connctions.
common::Time last_update_time_
boost::mutex lock_
mutex to lock access to fields that are used in message callbacks
double gaussian_noise_
Gaussian noise.
std::string topic_name_
topic name
ros::CallbackQueue range_queue_
sensors::SensorPtr parent_sensor_
The parent sensor.
boost::thread callback_queue_thread_
virtual void OnNewLaserScans()
Update the controller.
void PutRangeData(common::Time &_updateTime)
Put range data to the ROS topic.
double fov_
sensor field of view
boost::thread deferred_load_thread_