Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosVelodyneLaser Class Reference

#include <GazeboRosVelodyneLaser.h>

Inheritance diagram for gazebo::GazeboRosVelodyneLaser:
Inheritance graph
[legend]

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::NodeHandlenh_
 Pointer to ROS node. More...
 
bool organize_cloud_
 organize cloud 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...
 

Detailed Description

Definition at line 77 of file GazeboRosVelodyneLaser.h.

Constructor & Destructor Documentation

gazebo::GazeboRosVelodyneLaser::GazeboRosVelodyneLaser ( )

Constructor.

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

Definition at line 75 of file GazeboRosVelodyneLaser.cpp.

gazebo::GazeboRosVelodyneLaser::~GazeboRosVelodyneLaser ( )

Destructor.

Definition at line 81 of file GazeboRosVelodyneLaser.cpp.

Member Function Documentation

void gazebo::GazeboRosVelodyneLaser::ConnectCb ( )
private

Subscribe on-demand.

Definition at line 214 of file GazeboRosVelodyneLaser.cpp.

static double gazebo::GazeboRosVelodyneLaser::gaussianKernel ( double  mu,
double  sigma 
)
inlinestaticprivate

Gaussian noise generator.

Definition at line 124 of file GazeboRosVelodyneLaser.h.

void gazebo::GazeboRosVelodyneLaser::laserQueueThread ( )
private

Definition at line 392 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 97 of file GazeboRosVelodyneLaser.cpp.

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

Definition at line 237 of file GazeboRosVelodyneLaser.cpp.

Member Data Documentation

boost::thread gazebo::GazeboRosVelodyneLaser::callback_laser_queue_thread_
private

Definition at line 142 of file GazeboRosVelodyneLaser.h.

std::string gazebo::GazeboRosVelodyneLaser::frame_name_
private

frame transform name, should match link name

Definition at line 106 of file GazeboRosVelodyneLaser.h.

double gazebo::GazeboRosVelodyneLaser::gaussian_noise_
private

Gaussian noise.

Definition at line 121 of file GazeboRosVelodyneLaser.h.

gazebo::transport::NodePtr gazebo::GazeboRosVelodyneLaser::gazebo_node_
private

Definition at line 145 of file GazeboRosVelodyneLaser.h.

ros::CallbackQueue gazebo::GazeboRosVelodyneLaser::laser_queue_
private

Definition at line 140 of file GazeboRosVelodyneLaser.h.

boost::mutex gazebo::GazeboRosVelodyneLaser::lock_
private

A mutex to lock access.

Definition at line 134 of file GazeboRosVelodyneLaser.h.

double gazebo::GazeboRosVelodyneLaser::max_range_
private

Maximum range to publish.

Definition at line 118 of file GazeboRosVelodyneLaser.h.

double gazebo::GazeboRosVelodyneLaser::min_intensity_
private

the intensity beneath which points will be filtered

Definition at line 112 of file GazeboRosVelodyneLaser.h.

double gazebo::GazeboRosVelodyneLaser::min_range_
private

Minimum range to publish.

Definition at line 115 of file GazeboRosVelodyneLaser.h.

ros::NodeHandle* gazebo::GazeboRosVelodyneLaser::nh_
private

Pointer to ROS node.

Definition at line 97 of file GazeboRosVelodyneLaser.h.

bool gazebo::GazeboRosVelodyneLaser::organize_cloud_
private

organize cloud

Definition at line 109 of file GazeboRosVelodyneLaser.h.

sensors::RaySensorPtr gazebo::GazeboRosVelodyneLaser::parent_ray_sensor_
private

The parent ray sensor.

Definition at line 94 of file GazeboRosVelodyneLaser.h.

ros::Publisher gazebo::GazeboRosVelodyneLaser::pub_
private

ROS publisher.

Definition at line 100 of file GazeboRosVelodyneLaser.h.

std::string gazebo::GazeboRosVelodyneLaser::robot_namespace_
private

For setting ROS name space.

Definition at line 137 of file GazeboRosVelodyneLaser.h.

gazebo::transport::SubscriberPtr gazebo::GazeboRosVelodyneLaser::sub_
private

Definition at line 146 of file GazeboRosVelodyneLaser.h.

std::string gazebo::GazeboRosVelodyneLaser::topic_name_
private

topic name

Definition at line 103 of file GazeboRosVelodyneLaser.h.


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


velodyne_gazebo_plugins
Author(s): Kevin Hallenbeck
autogenerated on Fri Apr 2 2021 02:51:11