Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
gazebo::GazeboRosGpuLaser Class Reference

#include <gazebo_ros_gpu_laser.h>

List of all members.

Public Member Functions

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

Protected Member Functions

virtual void OnNewLaserFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller.
void PublishLaserScan (const float *_scan, unsigned int _width)
 Update the controller.
void PublishPointCloud (const float *_scan, unsigned int _width, unsigned int _height)
void QueueThread ()

Protected Attributes

boost::thread callback_queue_thread_
std::string frame_name_
ros::WallTime last_publish_
ros::CallbackQueue queue_
ros::NodeHandlerosnode_
double update_period_
double update_rate_

Private Member Functions

double GaussianKernel (double mu, double sigma)
 Gaussian noise generator.
void LaserConnect ()
void LaserDisconnect ()

Private Attributes

double gaussian_noise_
 Gaussian noise.
double hokuyo_min_intensity_
 hack to mimic hokuyo intensity cutoff of 100
int laser_connect_count_
 Keep track of number of connctions for point clouds.
sensor_msgs::LaserScan laser_scan_msg_
ros::Publisher laser_scan_pub_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string laser_topic_name_
 ROS image topic name.
double point_cloud_cutoff_
pcl::PointCloud< pcl::PointXYZIpoint_cloud_msg_
 PCL point cloud message.
std::string robot_namespace_
common::Time sensor_update_time_

Detailed Description

Definition at line 62 of file gazebo_ros_gpu_laser.h.


Constructor & Destructor Documentation

Constructor.

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

Definition at line 56 of file gazebo_ros_gpu_laser.cpp.

Destructor.

Definition at line 63 of file gazebo_ros_gpu_laser.cpp.


Member Function Documentation

double gazebo::GazeboRosGpuLaser::GaussianKernel ( double  mu,
double  sigma 
) [private]

Gaussian noise generator.

Definition at line 450 of file gazebo_ros_gpu_laser.cpp.

Definition at line 265 of file gazebo_ros_gpu_laser.cpp.

Definition at line 287 of file gazebo_ros_gpu_laser.cpp.

Definition at line 294 of file gazebo_ros_gpu_laser.cpp.

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

Load the plugin.

Parameters:
takein SDF root element

Definition at line 76 of file gazebo_ros_gpu_laser.cpp.

void gazebo::GazeboRosGpuLaser::OnNewLaserFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
) [protected, virtual]

Update the controller.

Definition at line 304 of file gazebo_ros_gpu_laser.cpp.

void gazebo::GazeboRosGpuLaser::PublishLaserScan ( const float *  _scan,
unsigned int  _width 
) [protected]

Update the controller.

Definition at line 328 of file gazebo_ros_gpu_laser.cpp.

void gazebo::GazeboRosGpuLaser::PublishPointCloud ( const float *  _scan,
unsigned int  _width,
unsigned int  _height 
) [protected]

Definition at line 377 of file gazebo_ros_gpu_laser.cpp.

take care of callback queue

Definition at line 466 of file gazebo_ros_gpu_laser.cpp.


Member Data Documentation

Definition at line 139 of file gazebo_ros_gpu_laser.h.

std::string gazebo::GazeboRosGpuLaser::frame_name_ [protected]

Definition at line 145 of file gazebo_ros_gpu_laser.h.

Gaussian noise.

Definition at line 104 of file gazebo_ros_gpu_laser.h.

hack to mimic hokuyo intensity cutoff of 100

Definition at line 111 of file gazebo_ros_gpu_laser.h.

Keep track of number of connctions for point clouds.

Definition at line 114 of file gazebo_ros_gpu_laser.h.

sensor_msgs::LaserScan gazebo::GazeboRosGpuLaser::laser_scan_msg_ [private]

Definition at line 124 of file gazebo_ros_gpu_laser.h.

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 119 of file gazebo_ros_gpu_laser.h.

ROS image topic name.

Definition at line 129 of file gazebo_ros_gpu_laser.h.

Definition at line 141 of file gazebo_ros_gpu_laser.h.

Definition at line 126 of file gazebo_ros_gpu_laser.h.

PCL point cloud message.

Definition at line 122 of file gazebo_ros_gpu_laser.h.

Definition at line 137 of file gazebo_ros_gpu_laser.h.

Definition at line 135 of file gazebo_ros_gpu_laser.h.

Definition at line 134 of file gazebo_ros_gpu_laser.h.

Definition at line 132 of file gazebo_ros_gpu_laser.h.

Definition at line 147 of file gazebo_ros_gpu_laser.h.

Definition at line 146 of file gazebo_ros_gpu_laser.h.


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


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 12:15:44