Go to the documentation of this file.
30 #ifndef RVIZ_POINT_CLOUD2_DISPLAY_H
31 #define RVIZ_POINT_CLOUD2_DISPLAY_H
33 #include <sensor_msgs/PointCloud2.h>
40 class PointCloudCommon;
59 void reset()
override;
61 void update(
float wall_dt,
float ros_dt)
override;
68 void processMessage(
const sensor_msgs::PointCloud2ConstPtr& cloud)
override;
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
~PointCloud2Display() override
Displays a point cloud of type sensor_msgs::PointCloud2.
void reset() override
Called to tell the display to clear its state.
void processMessage(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Process a single message. Overridden from MessageFilterDisplay.
Displays a point cloud of type sensor_msgs::PointCloud.
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
PointCloudCommon * point_cloud_common_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02