Public Member Functions | Protected Member Functions | Protected Attributes | Private Slots
rviz::LaserScanDisplay Class Reference

Visualizes a laser scan, received as a sensor_msgs::LaserScan. More...

#include <laser_scan_display.h>

Inheritance diagram for rviz::LaserScanDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 LaserScanDisplay ()
virtual void reset ()
 Called to tell the display to clear its state.
virtual void update (float wall_dt, float ros_dt)
 Called periodically by the visualization manager.
 ~LaserScanDisplay ()

Protected Member Functions

virtual void onInitialize ()
 Do initialization. Overridden from MessageFilterDisplay.
virtual void processMessage (const sensor_msgs::LaserScanConstPtr &scan)
 Process a single message. Overridden from MessageFilterDisplay.

Protected Attributes

ros::Duration filter_tolerance_
PointCloudCommonpoint_cloud_common_
laser_geometry::LaserProjectionprojector_
IntPropertyqueue_size_property_

Private Slots

void updateQueueSize ()

Detailed Description

Visualizes a laser scan, received as a sensor_msgs::LaserScan.

Definition at line 49 of file laser_scan_display.h.


Constructor & Destructor Documentation

Definition at line 49 of file laser_scan_display.cpp.

Definition at line 64 of file laser_scan_display.cpp.


Member Function Documentation

void rviz::LaserScanDisplay::onInitialize ( ) [protected, virtual]

Do initialization. Overridden from MessageFilterDisplay.

Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::LaserScan >.

Definition at line 70 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::processMessage ( const sensor_msgs::LaserScanConstPtr &  scan) [protected, virtual]

Process a single message. Overridden from MessageFilterDisplay.

Definition at line 81 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::reset ( ) [virtual]

Called to tell the display to clear its state.

Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::LaserScan >.

Definition at line 115 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Called periodically by the visualization manager.

Parameters:
wall_dtWall-clock time, in seconds, since the last time the update list was run through.
ros_dtROS time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 110 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::updateQueueSize ( ) [private, slot]

Definition at line 76 of file laser_scan_display.cpp.


Member Data Documentation

Definition at line 75 of file laser_scan_display.h.

Definition at line 72 of file laser_scan_display.h.

Definition at line 74 of file laser_scan_display.h.

Definition at line 70 of file laser_scan_display.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:37