Thin wrapper type for 2D sensor_msgs/LaserScan
messages.
More...
#include <laser_scan.hpp>
Thin wrapper type for 2D sensor_msgs/LaserScan
messages.
Definition at line 34 of file laser_scan.hpp.
◆ Scalar
◆ LaserScan()
beluga_ros::LaserScan::LaserScan |
( |
beluga_ros::msg::LaserScanConstSharedPtr |
scan, |
|
|
Sophus::SE3d |
origin = Sophus::SE3d() , |
|
|
std::size_t |
max_beams = std::numeric_limits<std::size_t>::max() , |
|
|
Scalar |
min_range = std::numeric_limits<Scalar>::min() , |
|
|
Scalar |
max_range = std::numeric_limits<Scalar>::max() |
|
) |
| |
|
inlineexplicit |
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). |
Definition at line 49 of file laser_scan.hpp.
◆ angles()
auto beluga_ros::LaserScan::angles |
( |
| ) |
const |
|
inline |
Get laser scan measurement angles as a range.
Definition at line 67 of file laser_scan.hpp.
◆ max_range()
auto beluga_ros::LaserScan::max_range |
( |
| ) |
const |
|
inline |
Get the maximum range measurement.
Definition at line 84 of file laser_scan.hpp.
◆ min_range()
auto beluga_ros::LaserScan::min_range |
( |
| ) |
const |
|
inline |
Get the minimum range measurement.
Definition at line 81 of file laser_scan.hpp.
◆ origin()
const auto& beluga_ros::LaserScan::origin |
( |
| ) |
const |
|
inline |
Get the laser scan frame origin in the filter frame.
Definition at line 64 of file laser_scan.hpp.
◆ ranges()
auto beluga_ros::LaserScan::ranges |
( |
| ) |
const |
|
inline |
Get laser scan range measurements as a range.
Definition at line 75 of file laser_scan.hpp.
◆ max_beams_
std::size_t beluga_ros::LaserScan::max_beams_ |
|
private |
◆ max_range_
Scalar beluga_ros::LaserScan::max_range_ |
|
private |
◆ min_range_
Scalar beluga_ros::LaserScan::min_range_ |
|
private |
◆ origin_
◆ scan_
beluga_ros::msg::LaserScanConstSharedPtr beluga_ros::LaserScan::scan_ |
|
private |
The documentation for this class was generated from the following file: