#include <GazeboRosVelodyneLaser.h>

Public Member Functions | |
| GazeboRosVelodyneLaser () | |
| Constructor. More... | |
| void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. More... | |
| void | onStats (const boost::shared_ptr< msgs::WorldStatistics const > &_msg) |
| ~GazeboRosVelodyneLaser () | |
| Destructor. More... | |
Protected Member Functions | |
| virtual void | OnNewLaserScans () |
| Update the controller. More... | |
Private Member Functions | |
| void | laserConnect () |
| void | laserDisconnect () |
| void | laserQueueThread () |
| void | putLaserData (common::Time &_updateTime) |
| Put laser data to the ROS topic. More... | |
Static Private Member Functions | |
| static double | gaussianKernel (double mu, double sigma) |
| Gaussian noise generator. More... | |
Private Attributes | |
| boost::thread | callback_laser_queue_thread_ |
| std::string | frame_name_ |
| frame transform name, should match link name More... | |
| double | gaussian_noise_ |
| Gaussian noise. More... | |
| int | laser_connect_count_ |
| Keep track of number of connections. More... | |
| ros::CallbackQueue | laser_queue_ |
| common::Time | last_update_time_ |
| boost::mutex | lock_ |
| A mutex to lock access to fields that are used in message callbacks. More... | |
| double | max_range_ |
| Maximum range to publish. More... | |
| double | min_range_ |
| Minimum range to publish. More... | |
| transport::NodePtr | node_ |
| sensors::RaySensorPtr | parent_ray_sensor_ |
| sensors::SensorPtr | parent_sensor_ |
| The parent sensor. More... | |
| ros::Publisher | pub_ |
| std::string | robot_namespace_ |
| for setting ROS name space More... | |
| ros::NodeHandle * | rosnode_ |
| pointer to ros node More... | |
| common::Time | sim_time_ |
| std::string | topic_name_ |
| topic name More... | |
| physics::WorldPtr | world_ |
Definition at line 59 of file GazeboRosVelodyneLaser.h.
| gazebo::GazeboRosVelodyneLaser::GazeboRosVelodyneLaser | ( | ) |
Constructor.
| parent | The parent entity, must be a Model or a Sensor |
Definition at line 61 of file GazeboRosVelodyneLaser.cpp.
| gazebo::GazeboRosVelodyneLaser::~GazeboRosVelodyneLaser | ( | ) |
Destructor.
Definition at line 67 of file GazeboRosVelodyneLaser.cpp.
|
inlinestaticprivate |
Gaussian noise generator.
Definition at line 111 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 191 of file GazeboRosVelodyneLaser.cpp.
|
private |
Definition at line 198 of file GazeboRosVelodyneLaser.cpp.
|
private |
Definition at line 411 of file GazeboRosVelodyneLaser.cpp.
| void gazebo::GazeboRosVelodyneLaser::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| take | in SDF root element |
Definition at line 83 of file GazeboRosVelodyneLaser.cpp.
|
protectedvirtual |
Update the controller.
Definition at line 208 of file GazeboRosVelodyneLaser.cpp.
| void gazebo::GazeboRosVelodyneLaser::onStats | ( | const boost::shared_ptr< msgs::WorldStatistics const > & | _msg | ) |
Definition at line 420 of file GazeboRosVelodyneLaser.cpp.
|
private |
Put laser data to the ROS topic.
Definition at line 227 of file GazeboRosVelodyneLaser.cpp.
|
private |
Definition at line 129 of file GazeboRosVelodyneLaser.h.
|
private |
frame transform name, should match link name
Definition at line 99 of file GazeboRosVelodyneLaser.h.
|
private |
Gaussian noise.
Definition at line 108 of file GazeboRosVelodyneLaser.h.
|
private |
Keep track of number of connections.
Definition at line 81 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 127 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 78 of file GazeboRosVelodyneLaser.h.
|
private |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 121 of file GazeboRosVelodyneLaser.h.
|
private |
Maximum range to publish.
Definition at line 105 of file GazeboRosVelodyneLaser.h.
|
private |
Minimum range to publish.
Definition at line 102 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 132 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 89 of file GazeboRosVelodyneLaser.h.
|
private |
The parent sensor.
Definition at line 88 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 93 of file GazeboRosVelodyneLaser.h.
|
private |
for setting ROS name space
Definition at line 124 of file GazeboRosVelodyneLaser.h.
|
private |
pointer to ros node
Definition at line 92 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 133 of file GazeboRosVelodyneLaser.h.
|
private |
topic name
Definition at line 96 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 86 of file GazeboRosVelodyneLaser.h.