Public Member Functions | Protected Member Functions | Protected Attributes
rviz::PointCloud2Display Class Reference

#include <point_cloud2_display.h>

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

List of all members.

Public Member Functions

virtual void createProperties ()
 Called from setPropertyManager, gives the display a chance to create some properties immediately.
virtual void fixedFrameChanged ()
 Override to handle changes to fixed_frame_. This base class implementation does nothing.
int getQueueSize ()
const std::string & getTopic ()
virtual void onInitialize ()
 Override this function to do subclass-specific initialization.
 PointCloud2Display ()
void setQueueSize (int size)
void setTopic (const std::string &topic)
 ~PointCloud2Display ()

Protected Member Functions

void incomingCloudCallback (const sensor_msgs::PointCloud2ConstPtr &cloud)
 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

IntPropertyWPtr queue_size_property_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub_
tf::MessageFilter
< sensor_msgs::PointCloud2 > * 
tf_filter_
std::string topic_
 The PointCloud topic set by setTopic()
ROSTopicStringPropertyWPtr topic_property_

Detailed Description

Definition at line 61 of file point_cloud2_display.h.


Constructor & Destructor Documentation

Definition at line 49 of file point_cloud2_display.cpp.

Definition at line 55 of file point_cloud2_display.cpp.


Member Function Documentation

Called from setPropertyManager, gives the display a chance to create some properties immediately.

When this function is called, the property_manager_ member is valid and will stay valid

Reimplemented from rviz::PointCloudBase.

Definition at line 196 of file point_cloud2_display.cpp.

Override to handle changes to fixed_frame_. This base class implementation does nothing.

Reimplemented from rviz::PointCloudBase.

Definition at line 189 of file point_cloud2_display.cpp.

Definition at line 80 of file point_cloud2_display.cpp.

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

Definition at line 78 of file point_cloud2_display.h.

void rviz::PointCloud2Display::incomingCloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  cloud) [protected]

ROS callback for an incoming point cloud message.

Definition at line 135 of file point_cloud2_display.cpp.

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

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

Reimplemented from rviz::PointCloudBase.

Definition at line 104 of file point_cloud2_display.cpp.

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

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

Reimplemented from rviz::PointCloudBase.

Definition at line 97 of file point_cloud2_display.cpp.

Override this function to do subclass-specific initialization.

This is called after vis_manager_ and scene_manager_ are set.

Reimplemented from rviz::PointCloudBase.

Definition at line 62 of file point_cloud2_display.cpp.

Set the incoming message queue size.

Definition at line 71 of file point_cloud2_display.cpp.

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

Set the incoming PointCloud topic

Parameters:
topicThe topic we should listen to

Definition at line 85 of file point_cloud2_display.cpp.

Subscribes to the topic set by setTopic()

Definition at line 112 of file point_cloud2_display.cpp.

Unsubscribes from the current topic.

Definition at line 130 of file point_cloud2_display.cpp.


Member Data Documentation

Definition at line 108 of file point_cloud2_display.h.

message_filters::Subscriber<sensor_msgs::PointCloud2> rviz::PointCloud2Display::sub_ [protected]

Definition at line 104 of file point_cloud2_display.h.

tf::MessageFilter<sensor_msgs::PointCloud2>* rviz::PointCloud2Display::tf_filter_ [protected]

Definition at line 105 of file point_cloud2_display.h.

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

The PointCloud topic set by setTopic()

Definition at line 102 of file point_cloud2_display.h.

ROSTopicStringPropertyWPtr rviz::PointCloud2Display::topic_property_ [protected]

Definition at line 107 of file point_cloud2_display.h.


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


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33