#include <lj_laser.h>
Public Member Functions | |
LJLaser (const std::string &name, const std::string &interface_name, const std::string &set_service_name) | |
void | onLearn () |
void | onStop () |
Private Member Functions | |
double | completion () |
void | handleLaser (sensor_msgs::LaserScan msg) |
callback function processing laser scans | |
Private Attributes | |
bool | assigned_ |
true as first laser scan is added to the descriptor | |
std::vector < sensor_msgs::LaserScan > | descriptor_ |
descriptor to save on stop | |
std::string | interface_name_ |
ros::Subscriber | laser_scan_subscriber_ |
keep the subscriber to allow subscribe/un-subscribe as start/stop/interrupt/continue is called | |
sensor_msgs::LaserScan | previous_laser_scan_ |
previously received sensor message kept | |
sensor_msgs::LaserScan | reference_laser_scan_ |
laser scan added to the descriptor at last | |
std::string | set_service_name_ |
Definition at line 15 of file lj_laser.h.
LJLaser::LJLaser | ( | const std::string & | name, |
const std::string & | interface_name, | ||
const std::string & | set_service_name | ||
) |
Definition at line 4 of file lj_laser.cpp.
double LJLaser::completion | ( | ) | [private] |
Definition at line 111 of file lj_laser.cpp.
void LJLaser::handleLaser | ( | sensor_msgs::LaserScan | msg | ) | [private] |
callback function processing laser scans
Definition at line 80 of file lj_laser.cpp.
void LJLaser::onLearn | ( | ) | [virtual] |
Implements lama_jockeys::LearningJockey.
Definition at line 14 of file lj_laser.cpp.
void LJLaser::onStop | ( | ) | [virtual] |
Implements lama_jockeys::LearningJockey.
Definition at line 66 of file lj_laser.cpp.
bool LJLaser::assigned_ [private] |
true as first laser scan is added to the descriptor
Definition at line 34 of file lj_laser.h.
std::vector<sensor_msgs::LaserScan> LJLaser::descriptor_ [private] |
descriptor to save on stop
Definition at line 36 of file lj_laser.h.
std::string LJLaser::interface_name_ [private] |
Definition at line 29 of file lj_laser.h.
keep the subscriber to allow subscribe/un-subscribe as start/stop/interrupt/continue is called
Definition at line 32 of file lj_laser.h.
sensor_msgs::LaserScan LJLaser::previous_laser_scan_ [private] |
previously received sensor message kept
Definition at line 38 of file lj_laser.h.
sensor_msgs::LaserScan LJLaser::reference_laser_scan_ [private] |
laser scan added to the descriptor at last
Definition at line 37 of file lj_laser.h.
std::string LJLaser::set_service_name_ [private] |
Definition at line 30 of file lj_laser.h.