The container of the laser range finder. More...
#include <crsm_laser.h>
Public Member Functions | |
CrsmLaser (void) | |
Default constructor. Initialises the CrsmLaser::initialised flag to false. | |
void | initialize (const sensor_msgs::LaserScanConstPtr &msg) |
Initialises the CrsmLaserInfo and CrsmLaserScan when the first scan arrives. | |
Public Attributes | |
std::vector< float > | angles |
Laser rays's angles with regard to the robot's orientation. | |
CrsmLaserInfo | info |
Container for the map info in the form of a CrsmLaserInfo structure. | |
bool | initialized |
This flag becomes true when the first laser scan arrives. | |
CrsmLaserScan | scan |
Holds the current laserScan in a CrsmLaserScan structure. |
The container of the laser range finder.
Definition at line 36 of file crsm_laser.h.
crsm_slam::CrsmLaser::CrsmLaser | ( | void | ) |
Default constructor. Initialises the CrsmLaser::initialised flag to false.
Definition at line 27 of file crsm_laser.cpp.
void crsm_slam::CrsmLaser::initialize | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) |
Initialises the CrsmLaserInfo and CrsmLaserScan when the first scan arrives.
msg | [const sensor_msgs::LaserScanConstPtr&] The sensor_msgs::LaserScan message |
Definition at line 36 of file crsm_laser.cpp.
std::vector<float> crsm_slam::CrsmLaser::angles |
Laser rays's angles with regard to the robot's orientation.
Definition at line 42 of file crsm_laser.h.
Container for the map info in the form of a CrsmLaserInfo structure.
Definition at line 40 of file crsm_laser.h.
This flag becomes true when the first laser scan arrives.
Definition at line 38 of file crsm_laser.h.
Holds the current laserScan in a CrsmLaserScan structure.
Definition at line 41 of file crsm_laser.h.