#include <GazeboRosVelodyneLaser.h>
Public Member Functions | |
GazeboRosVelodyneLaser () | |
Constructor. More... | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. More... | |
~GazeboRosVelodyneLaser () | |
Destructor. More... | |
Private Member Functions | |
void | ConnectCb () |
Subscribe on-demand. More... | |
void | laserQueueThread () |
void | OnScan (const ConstLaserScanStampedPtr &_msg) |
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... | |
gazebo::transport::NodePtr | gazebo_node_ |
ros::CallbackQueue | laser_queue_ |
boost::mutex | lock_ |
A mutex to lock access. More... | |
double | max_range_ |
Maximum range to publish. More... | |
double | min_intensity_ |
the intensity beneath which points will be filtered More... | |
double | min_range_ |
Minimum range to publish. More... | |
ros::NodeHandle * | nh_ |
Pointer to ROS node. More... | |
sensors::RaySensorPtr | parent_ray_sensor_ |
The parent ray sensor. More... | |
ros::Publisher | pub_ |
ROS publisher. More... | |
std::string | robot_namespace_ |
For setting ROS name space. More... | |
gazebo::transport::SubscriberPtr | sub_ |
std::string | topic_name_ |
topic name More... | |
Definition at line 77 of file GazeboRosVelodyneLaser.h.
gazebo::GazeboRosVelodyneLaser::GazeboRosVelodyneLaser | ( | ) |
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 73 of file GazeboRosVelodyneLaser.cpp.
gazebo::GazeboRosVelodyneLaser::~GazeboRosVelodyneLaser | ( | ) |
Destructor.
Definition at line 79 of file GazeboRosVelodyneLaser.cpp.
|
private |
Subscribe on-demand.
Definition at line 205 of file GazeboRosVelodyneLaser.cpp.
|
inlinestaticprivate |
Gaussian noise generator.
Definition at line 121 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 369 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 95 of file GazeboRosVelodyneLaser.cpp.
|
private |
Definition at line 228 of file GazeboRosVelodyneLaser.cpp.
|
private |
Definition at line 139 of file GazeboRosVelodyneLaser.h.
|
private |
frame transform name, should match link name
Definition at line 106 of file GazeboRosVelodyneLaser.h.
|
private |
Gaussian noise.
Definition at line 118 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 142 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 137 of file GazeboRosVelodyneLaser.h.
|
private |
A mutex to lock access.
Definition at line 131 of file GazeboRosVelodyneLaser.h.
|
private |
Maximum range to publish.
Definition at line 115 of file GazeboRosVelodyneLaser.h.
|
private |
the intensity beneath which points will be filtered
Definition at line 109 of file GazeboRosVelodyneLaser.h.
|
private |
Minimum range to publish.
Definition at line 112 of file GazeboRosVelodyneLaser.h.
|
private |
Pointer to ROS node.
Definition at line 97 of file GazeboRosVelodyneLaser.h.
|
private |
The parent ray sensor.
Definition at line 94 of file GazeboRosVelodyneLaser.h.
|
private |
ROS publisher.
Definition at line 100 of file GazeboRosVelodyneLaser.h.
|
private |
For setting ROS name space.
Definition at line 134 of file GazeboRosVelodyneLaser.h.
|
private |
Definition at line 143 of file GazeboRosVelodyneLaser.h.
|
private |
topic name
Definition at line 103 of file GazeboRosVelodyneLaser.h.