Class PointCloud2Display
Defined in File point_cloud2_display.hpp
Inheritance Relationships
Base Type
public rviz_default_plugins::displays::PointCloud2TransportDisplay< sensor_msgs::msg::PointCloud2 >
(Template Class PointCloud2TransportDisplay)
Class Documentation
-
class PointCloud2Display : public rviz_default_plugins::displays::PointCloud2TransportDisplay<sensor_msgs::msg::PointCloud2>
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.
Public Functions
-
PointCloud2Display()
-
void reset() override
-
void update(float wall_dt, float ros_dt) override
Filter any NAN values out of the cloud. Any NAN values that make it through to PointCloudBase will get their points put off in lala land, but it means they still do get processed/rendered which can be a big performance hit
- Parameters:
cloud – The cloud to be filtered
- Returns:
A new cloud containing only the filtered points
Move to public for testing.
Move to public for testing.
-
void onDisable() override
Protected Functions
-
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Process a single message. Overridden from MessageFilterDisplay.
-
PointCloud2Display()