LaserScan Class Reference#
|
Beluga ROS
|
beluga_ros::LaserScan Class Reference
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
More...
#include <laser_scan.hpp>
Inheritance diagram for beluga_ros::LaserScan:
Collaboration diagram for beluga_ros::LaserScan:
Public Types | |
| using | Scalar = double |
| Range type. | |
Public Member Functions | |
| LaserScan (sensor_msgs::msg::LaserScan::ConstSharedPtr 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()) | |
| const auto & | origin () const |
| Get the laser scan frame origin in the filter frame. | |
| auto | angles () const |
| Get laser scan measurement angles as a range. | |
| auto | ranges () const |
| Get laser scan range measurements as a range. | |
| std::size_t | size () const |
| Get the number of beams in the scan. | |
| auto | min_range () const |
| Get the minimum range measurement. | |
| auto | max_range () const |
| Get the maximum range measurement. | |
Public Member Functions inherited from beluga::BaseLaserScan< LaserScan > | |
| auto | points_in_cartesian_coordinates () const |
| auto | points_in_polar_coordinates () const |
Detailed Description
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Constructor & Destructor Documentation
◆ LaserScan()
|
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).
The documentation for this class was generated from the following file:
- /home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/laser_scan.hpp
Generated by
Public Member Functions inherited from