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;
60 void updateQueueSize();
64 void onInitialize()
override;
67 void processMessage(
const sensor_msgs::LaserScanConstPtr& scan)
override;
70 void checkTolerance(
int tolerance);
laser_geometry::LaserProjection * projector_
Property specialized to provide max/min enforcement for integers.
Displays a point cloud of type sensor_msgs::PointCloud.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
IntProperty * queue_size_property_
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
ros::Duration filter_tolerance_
PointCloudCommon * point_cloud_common_