Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
gazebo::GazeboRosVelodyneLaser Class Reference

#include <GazeboRosVelodyneLaser.h>

List of all members.

Public Member Functions

 GazeboRosVelodyneLaser ()
 Constructor.
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin.
 ~GazeboRosVelodyneLaser ()
 Destructor.

Private Member Functions

void ConnectCb ()
 Subscribe on-demand.
void laserQueueThread ()
void OnScan (const ConstLaserScanStampedPtr &_msg)

Static Private Member Functions

static double gaussianKernel (double mu, double sigma)
 Gaussian noise generator.

Private Attributes

boost::thread callback_laser_queue_thread_
std::string frame_name_
 frame transform name, should match link name
double gaussian_noise_
 Gaussian noise.
gazebo::transport::NodePtr gazebo_node_
ros::CallbackQueue laser_queue_
boost::mutex lock_
 A mutex to lock access.
double max_range_
 Maximum range to publish.
double min_range_
 Minimum range to publish.
ros::NodeHandlenh_
 Pointer to ROS node.
sensors::RaySensorPtr parent_ray_sensor_
 The parent ray sensor.
ros::Publisher pub_
 ROS publisher.
std::string robot_namespace_
 For setting ROS name space.
gazebo::transport::SubscriberPtr sub_
std::string topic_name_
 topic name

Detailed Description

Definition at line 61 of file GazeboRosVelodyneLaser.h.


Constructor & Destructor Documentation

Constructor.

Parameters:
parentThe parent entity, must be a Model or a Sensor

Definition at line 60 of file GazeboRosVelodyneLaser.cpp.

Destructor.

Definition at line 66 of file GazeboRosVelodyneLaser.cpp.


Member Function Documentation

Subscribe on-demand.

Definition at line 181 of file GazeboRosVelodyneLaser.cpp.

static double gazebo::GazeboRosVelodyneLaser::gaussianKernel ( double  mu,
double  sigma 
) [inline, static, private]

Gaussian noise generator.

Definition at line 102 of file GazeboRosVelodyneLaser.h.

Definition at line 330 of file GazeboRosVelodyneLaser.cpp.

void gazebo::GazeboRosVelodyneLaser::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the plugin.

Parameters:
takein SDF root element

Definition at line 82 of file GazeboRosVelodyneLaser.cpp.

void gazebo::GazeboRosVelodyneLaser::OnScan ( const ConstLaserScanStampedPtr &  _msg) [private]

Definition at line 204 of file GazeboRosVelodyneLaser.cpp.


Member Data Documentation

Definition at line 120 of file GazeboRosVelodyneLaser.h.

frame transform name, should match link name

Definition at line 90 of file GazeboRosVelodyneLaser.h.

Gaussian noise.

Definition at line 99 of file GazeboRosVelodyneLaser.h.

gazebo::transport::NodePtr gazebo::GazeboRosVelodyneLaser::gazebo_node_ [private]

Definition at line 123 of file GazeboRosVelodyneLaser.h.

Definition at line 118 of file GazeboRosVelodyneLaser.h.

boost::mutex gazebo::GazeboRosVelodyneLaser::lock_ [private]

A mutex to lock access.

Definition at line 112 of file GazeboRosVelodyneLaser.h.

Maximum range to publish.

Definition at line 96 of file GazeboRosVelodyneLaser.h.

Minimum range to publish.

Definition at line 93 of file GazeboRosVelodyneLaser.h.

Pointer to ROS node.

Definition at line 81 of file GazeboRosVelodyneLaser.h.

sensors::RaySensorPtr gazebo::GazeboRosVelodyneLaser::parent_ray_sensor_ [private]

The parent ray sensor.

Definition at line 78 of file GazeboRosVelodyneLaser.h.

ROS publisher.

Definition at line 84 of file GazeboRosVelodyneLaser.h.

For setting ROS name space.

Definition at line 115 of file GazeboRosVelodyneLaser.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosVelodyneLaser::sub_ [private]

Definition at line 124 of file GazeboRosVelodyneLaser.h.

topic name

Definition at line 87 of file GazeboRosVelodyneLaser.h.


The documentation for this class was generated from the following files:


velodyne_gazebo_plugins
Author(s): Kevin Hallenbeck
autogenerated on Tue Sep 26 2017 03:02:17