Go to the documentation of this file.
30 #ifndef RVIZ_LASER_SCAN_DISPLAY_H
31 #define RVIZ_LASER_SCAN_DISPLAY_H
33 #include <sensor_msgs/LaserScan.h>
39 class LaserProjection;
45 class PointCloudCommon;
55 void reset()
override;
57 void update(
float wall_dt,
float ros_dt)
override;
64 void processMessage(
const sensor_msgs::LaserScanConstPtr& scan)
override;
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
void processMessage(const sensor_msgs::LaserScanConstPtr &scan) override
Process a single message. Overridden from MessageFilterDisplay.
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void checkTolerance(int tolerance)
void reset() override
Called to tell the display to clear its state.
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
Displays a point cloud of type sensor_msgs::PointCloud.
~LaserScanDisplay() override
ros::Duration filter_tolerance_
PointCloudCommon * point_cloud_common_
laser_geometry::LaserProjection * projector_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09