Displays a point cloud of type sensor_msgs::PointCloud2. More...
#include <point_cloud2_display.h>
Public Member Functions | |
PointCloud2Display () | |
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. | |
~PointCloud2Display () | |
Protected Member Functions | |
virtual void | onInitialize () |
Do initialization. Overridden from MessageFilterDisplay. | |
virtual void | processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) |
Process a single message. Overridden from MessageFilterDisplay. | |
Protected Attributes | |
PointCloudCommon * | point_cloud_common_ |
IntProperty * | queue_size_property_ |
Private Slots | |
void | updateQueueSize () |
Displays a point cloud of type sensor_msgs::PointCloud2.
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 51 of file point_cloud2_display.h.
Definition at line 48 of file point_cloud2_display.cpp.
Definition at line 62 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::onInitialize | ( | ) | [protected, virtual] |
Do initialization. Overridden from MessageFilterDisplay.
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 >.
Definition at line 67 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::processMessage | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected, virtual] |
Process a single message. Overridden from MessageFilterDisplay.
Definition at line 78 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 >.
Definition at line 172 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Called periodically by the visualization manager.
wall_dt | Wall-clock time, in seconds, since the last time the update list was run through. |
ros_dt | ROS time, in seconds, since the last time the update list was run through. |
Reimplemented from rviz::Display.
Definition at line 167 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::updateQueueSize | ( | ) | [private, slot] |
Definition at line 73 of file point_cloud2_display.cpp.
Definition at line 74 of file point_cloud2_display.h.
Definition at line 72 of file point_cloud2_display.h.