30 #ifndef RVIZ_POINT_CLOUD2_DISPLAY_H 31 #define RVIZ_POINT_CLOUD2_DISPLAY_H 33 #include <sensor_msgs/PointCloud2.h> 41 class PointCloudCommon;
60 virtual void update(
float wall_dt,
float ros_dt );
70 virtual void processMessage(
const sensor_msgs::PointCloud2ConstPtr& cloud );
virtual void reset()
Called to tell the display to clear its state.
Property specialized to provide max/min enforcement for integers.
Displays a point cloud of type sensor_msgs::PointCloud.
IntProperty * queue_size_property_
Display subclass using a tf::MessageFilter, templated on the ROS message type.
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual void processMessage(const sensor_msgs::PointCloud2ConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
Displays a point cloud of type sensor_msgs::PointCloud2.
PointCloudCommon * point_cloud_common_
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.