Displays a point cloud of type sensor_msgs::PointCloud. More...
#include <point_cloud_display.h>

| 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 () | 
| void | onInitialize () | 
| Override this function to do subclass-specific initialization. | |
| PointCloudDisplay () | |
| void | setQueueSize (int size) | 
| void | setTopic (const std::string &topic) | 
| ~PointCloudDisplay () | |
| Protected Member Functions | |
| void | incomingCloudCallback (const sensor_msgs::PointCloudConstPtr &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::PointCloud > | sub_ | 
| tf::MessageFilter < sensor_msgs::PointCloud > * | tf_filter_ | 
| std::string | topic_ | 
| The PointCloud topic set by setTopic() | |
| ROSTopicStringPropertyWPtr | topic_property_ | 
Displays a point cloud of type sensor_msgs::PointCloud.
By default it will assume channel 0 of the cloud is an intensity value, and will color them by intensity. If you set the channel's name to "rgb", it will interpret the channel as an integer rgb value, with r, g and b all being 8 bits.
Definition at line 61 of file point_cloud_display.h.
Definition at line 47 of file point_cloud_display.cpp.
Definition at line 53 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::createProperties | ( | ) |  [virtual] | 
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 145 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::PointCloudBase.
Definition at line 138 of file point_cloud_display.cpp.
Definition at line 78 of file point_cloud_display.cpp.
| const std::string& rviz::PointCloudDisplay::getTopic | ( | ) |  [inline] | 
Definition at line 78 of file point_cloud_display.h.
| void rviz::PointCloudDisplay::incomingCloudCallback | ( | const sensor_msgs::PointCloudConstPtr & | cloud | ) |  [protected] | 
ROS callback for an incoming point cloud message.
Definition at line 133 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::onDisable | ( | ) |  [protected, virtual] | 
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 102 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::onEnable | ( | ) |  [protected, virtual] | 
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 95 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::onInitialize | ( | ) |  [virtual] | 
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 60 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::setQueueSize | ( | int | size | ) | 
Set the incoming message queue size.
Definition at line 69 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::setTopic | ( | const std::string & | topic | ) | 
Set the incoming PointCloud topic
| topic | The topic we should listen to | 
Definition at line 83 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::subscribe | ( | ) |  [protected] | 
Subscribes to the topic set by setTopic()
Definition at line 110 of file point_cloud_display.cpp.
| void rviz::PointCloudDisplay::unsubscribe | ( | ) |  [protected] | 
Unsubscribes from the current topic.
Definition at line 128 of file point_cloud_display.cpp.
| IntPropertyWPtr rviz::PointCloudDisplay::queue_size_property_  [protected] | 
Definition at line 108 of file point_cloud_display.h.
Definition at line 104 of file point_cloud_display.h.
Definition at line 105 of file point_cloud_display.h.
| std::string rviz::PointCloudDisplay::topic_  [protected] | 
The PointCloud topic set by setTopic()
Definition at line 102 of file point_cloud_display.h.
| ROSTopicStringPropertyWPtr rviz::PointCloudDisplay::topic_property_  [protected] | 
Definition at line 107 of file point_cloud_display.h.