Class PointCloudDisplay

Inheritance Relationships

Base Type

  • public rviz_common::MessageFilterDisplay< sensor_msgs::msg::PointCloud >

Class Documentation

class PointCloudDisplay : public rviz_common::MessageFilterDisplay<sensor_msgs::msg::PointCloud>

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.

Public Functions

PointCloudDisplay()
void reset() override
void update(float wall_dt, float ros_dt) override
void onDisable() override

Protected Functions

void onInitialize() override

Do initialization. Overridden from MessageFilterDisplay.

void processMessage(sensor_msgs::msg::PointCloud::ConstSharedPtr cloud) override

Process a single message. Overridden from MessageFilterDisplay.

Protected Attributes

std::unique_ptr<PointCloudCommon> point_cloud_common_