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

virtual void createProperties ()
virtual void fixedFrameChanged ()
 Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
int getQueueSize ()
const std::string & getTopic ()
 LaserScanDisplay ()
virtual void onInitialize ()
 Override this function to do subclass-specific initialization.
void setQueueSize (int size)
void setTopic (const std::string &topic)
 ~LaserScanDisplay ()

Protected Member Functions

void incomingScanCallback (const sensor_msgs::LaserScan::ConstPtr &scan)
 ROS callback for an incoming point cloud message.
virtual void onDisable ()
 Derived classes override this to do the actual work of disabling themselves.
virtual void onEnable ()
 Derived classes override this to do the actual work of enabling themselves.
void subscribe ()
 Subscribes to the topic set by setTopic().
void unsubscribe ()
 Unsubscribes from the current topic.

Protected Attributes

ros::Duration filter_tolerance_
laser_geometry::LaserProjection * projector_
IntPropertyqueue_size_property_
message_filters::Subscriber
< sensor_msgs::LaserScan > 
sub_
tf::MessageFilter
< sensor_msgs::LaserScan > * 
tf_filter_
std::string topic_
 The PointCloud topic set by setTopic().
RosTopicPropertytopic_property_

Detailed Description

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

Definition at line 63 of file laser_scan_display.h.


Constructor & Destructor Documentation

rviz::LaserScanDisplay::LaserScanDisplay (  ) 

Definition at line 43 of file laser_scan_display.cpp.

rviz::LaserScanDisplay::~LaserScanDisplay (  ) 

Definition at line 48 of file laser_scan_display.cpp.


Member Function Documentation

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

Definition at line 168 of file laser_scan_display.cpp.

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

Called by setFixedFrame(). Override to respond to changes to fixed_frame_.

Reimplemented from rviz::PointCloudBase.

Definition at line 161 of file laser_scan_display.cpp.

int rviz::LaserScanDisplay::getQueueSize (  ) 

Definition at line 76 of file laser_scan_display.cpp.

const std::string& rviz::LaserScanDisplay::getTopic (  )  [inline]

Definition at line 80 of file laser_scan_display.h.

void rviz::LaserScanDisplay::incomingScanCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan  )  [protected]

ROS callback for an incoming point cloud message.

Definition at line 135 of file laser_scan_display.cpp.

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

Derived classes override this to do the actual work of disabling themselves.

Reimplemented from rviz::PointCloudBase.

Definition at line 103 of file laser_scan_display.cpp.

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

Derived classes override this to do the actual work of enabling themselves.

Reimplemented from rviz::PointCloudBase.

Definition at line 96 of file laser_scan_display.cpp.

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

Override this function to do subclass-specific initialization.

This is called after vis_manager_ and scene_manager_ are set, and before load() or setEnabled().

setName() may or may not have been called before this.

Reimplemented from rviz::PointCloudBase.

Definition at line 56 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::setQueueSize ( int  size  ) 

Set the incoming message queue size.

Definition at line 67 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::setTopic ( const std::string &  topic  ) 

Set the incoming PointCloud topic

Parameters:
topic The topic we should listen to

Definition at line 81 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::subscribe (  )  [protected]

Subscribes to the topic set by setTopic().

Definition at line 110 of file laser_scan_display.cpp.

void rviz::LaserScanDisplay::unsubscribe (  )  [protected]

Unsubscribes from the current topic.

Definition at line 128 of file laser_scan_display.cpp.


Member Data Documentation

ros::Duration rviz::LaserScanDisplay::filter_tolerance_ [protected]

Definition at line 112 of file laser_scan_display.h.

laser_geometry::LaserProjection* rviz::LaserScanDisplay::projector_ [protected]

Definition at line 110 of file laser_scan_display.h.

Definition at line 113 of file laser_scan_display.h.

message_filters::Subscriber<sensor_msgs::LaserScan> rviz::LaserScanDisplay::sub_ [protected]

Definition at line 105 of file laser_scan_display.h.

tf::MessageFilter<sensor_msgs::LaserScan>* rviz::LaserScanDisplay::tf_filter_ [protected]

Definition at line 106 of file laser_scan_display.h.

std::string rviz::LaserScanDisplay::topic_ [protected]

The PointCloud topic set by setTopic().

Definition at line 104 of file laser_scan_display.h.

Definition at line 108 of file laser_scan_display.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Wed Jun 6 11:25:47 2012