#include <gazebo_ros_range.h>
Public Member Functions | |
| GazeboRosRange () | |
| Constructor. | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. | |
| ~GazeboRosRange () | |
| Destructor. | |
Protected Member Functions | |
| virtual void | OnNewLaserScans () |
| Update the controller. | |
Private Member Functions | |
| double | GaussianKernel (double mu, double sigma) |
| Gaussian noise generator. | |
| void | LoadThread () |
| void | PutRangeData (common::Time &_updateTime) |
| Put range data to the ROS topic. | |
| void | RangeConnect () |
| void | RangeDisconnect () |
| void | RangeQueueThread () |
Private Attributes | |
| boost::thread | callback_queue_thread_ |
| boost::thread | deferred_load_thread_ |
| double | fov_ |
| sensor field of view | |
| std::string | frame_name_ |
| frame transform name, should match link name | |
| double | gaussian_noise_ |
| Gaussian noise. | |
| double | hokuyo_min_intensity_ |
| hack to mimic hokuyo intensity cutoff of 100 | |
| common::Time | last_update_time_ |
| boost::mutex | lock_ |
| mutex to lock access to fields that are used in message callbacks | |
| sensors::RaySensorPtr | parent_ray_sensor_ |
| sensors::SensorPtr | parent_sensor_ |
| The parent sensor. | |
| ros::Publisher | pub_ |
| std::string | radiation_ |
| radiation type : ultrasound or infrared | |
| int | range_connect_count_ |
| Keep track of number of connctions. | |
| sensor_msgs::Range | range_msg_ |
| ros message | |
| ros::CallbackQueue | range_queue_ |
| std::string | robot_namespace_ |
| for setting ROS name space | |
| ros::NodeHandle * | rosnode_ |
| pointer to ros node | |
| sdf::ElementPtr | sdf |
| unsigned int | seed |
| std::string | topic_name_ |
| topic name | |
| double | update_period_ |
| double | update_rate_ |
| update rate of this sensor | |
| physics::WorldPtr | world_ |
Definition at line 66 of file gazebo_ros_range.h.
Constructor.
Definition at line 63 of file gazebo_ros_range.cpp.
Destructor.
Definition at line 70 of file gazebo_ros_range.cpp.
| double gazebo::GazeboRosRange::GaussianKernel | ( | double | mu, |
| double | sigma | ||
| ) | [private] |
Gaussian noise generator.
Definition at line 330 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| take | in SDF root element |
Definition at line 82 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::LoadThread | ( | ) | [private] |
Definition at line 201 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::OnNewLaserScans | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 251 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::PutRangeData | ( | common::Time & | _updateTime | ) | [private] |
Put range data to the ROS topic.
Definition at line 276 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::RangeConnect | ( | ) | [private] |
Definition at line 233 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::RangeDisconnect | ( | ) | [private] |
Definition at line 240 of file gazebo_ros_range.cpp.
| void gazebo::GazeboRosRange::RangeQueueThread | ( | ) | [private] |
Definition at line 354 of file gazebo_ros_range.cpp.
boost::thread gazebo::GazeboRosRange::callback_queue_thread_ [private] |
Definition at line 136 of file gazebo_ros_range.h.
boost::thread gazebo::GazeboRosRange::deferred_load_thread_ [private] |
Definition at line 141 of file gazebo_ros_range.h.
double gazebo::GazeboRosRange::fov_ [private] |
sensor field of view
Definition at line 113 of file gazebo_ros_range.h.
std::string gazebo::GazeboRosRange::frame_name_ [private] |
frame transform name, should match link name
Definition at line 107 of file gazebo_ros_range.h.
double gazebo::GazeboRosRange::gaussian_noise_ [private] |
Gaussian noise.
Definition at line 115 of file gazebo_ros_range.h.
double gazebo::GazeboRosRange::hokuyo_min_intensity_ [private] |
hack to mimic hokuyo intensity cutoff of 100
Definition at line 124 of file gazebo_ros_range.h.
common::Time gazebo::GazeboRosRange::last_update_time_ [private] |
Definition at line 129 of file gazebo_ros_range.h.
boost::mutex gazebo::GazeboRosRange::lock_ [private] |
mutex to lock access to fields that are used in message callbacks
Definition at line 121 of file gazebo_ros_range.h.
sensors::RaySensorPtr gazebo::GazeboRosRange::parent_ray_sensor_ [private] |
Definition at line 94 of file gazebo_ros_range.h.
sensors::SensorPtr gazebo::GazeboRosRange::parent_sensor_ [private] |
The parent sensor.
Definition at line 93 of file gazebo_ros_range.h.
ros::Publisher gazebo::GazeboRosRange::pub_ [private] |
Definition at line 98 of file gazebo_ros_range.h.
std::string gazebo::GazeboRosRange::radiation_ [private] |
radiation type : ultrasound or infrared
Definition at line 110 of file gazebo_ros_range.h.
int gazebo::GazeboRosRange::range_connect_count_ [private] |
Keep track of number of connctions.
Definition at line 86 of file gazebo_ros_range.h.
sensor_msgs::Range gazebo::GazeboRosRange::range_msg_ [private] |
ros message
Definition at line 101 of file gazebo_ros_range.h.
Definition at line 134 of file gazebo_ros_range.h.
std::string gazebo::GazeboRosRange::robot_namespace_ [private] |
for setting ROS name space
Definition at line 132 of file gazebo_ros_range.h.
ros::NodeHandle* gazebo::GazeboRosRange::rosnode_ [private] |
pointer to ros node
Definition at line 97 of file gazebo_ros_range.h.
sdf::ElementPtr gazebo::GazeboRosRange::sdf [private] |
Definition at line 139 of file gazebo_ros_range.h.
unsigned int gazebo::GazeboRosRange::seed [private] |
Definition at line 142 of file gazebo_ros_range.h.
std::string gazebo::GazeboRosRange::topic_name_ [private] |
topic name
Definition at line 104 of file gazebo_ros_range.h.
double gazebo::GazeboRosRange::update_period_ [private] |
Definition at line 128 of file gazebo_ros_range.h.
double gazebo::GazeboRosRange::update_rate_ [private] |
update rate of this sensor
Definition at line 127 of file gazebo_ros_range.h.
physics::WorldPtr gazebo::GazeboRosRange::world_ [private] |
Definition at line 91 of file gazebo_ros_range.h.