Class LaserScan
Defined in File laser_scan.hpp
Inheritance Relationships
Base Type
public beluga::BaseLaserScan< LaserScan >
Class Documentation
-
class LaserScan : public beluga::BaseLaserScan<LaserScan>
Thin wrapper type for 2D
sensor_msgs/LaserScan
messages.Public Types
-
using Scalar = double
Range type.
Public Functions
Constructor.
- Parameters:
scan – Laser scan message.
origin – Laser scan frame origin in the filter frame. Note it is a transform in 3D because the frame lidars typically report data in is in general not coplanar with the plane on which 2D localization operates.
max_beams – Maximum number of beams to consider.
min_range – Minimum allowed range value (in meters).
max_range – Maximum allowed range value (in meters).
-
inline const auto &origin() const
Get the laser scan frame origin in the filter frame.
-
inline auto angles() const
Get laser scan measurement angles as a range.
-
inline auto ranges() const
Get laser scan range measurements as a range.
-
inline std::size_t size() const
Get the number of beams in the scan.
-
inline auto min_range() const
Get the minimum range measurement.
-
inline auto max_range() const
Get the maximum range measurement.
-
using Scalar = double