#include <nj_laser.h>

Public Member Functions | |
| NJLaser (const std::string &name, const std::string &get_service_name) | |
| virtual void | onContinue () |
| virtual void | onInterrupt () |
| virtual void | onStop () |
| virtual void | onTraverse () |
Private Member Functions | |
| double | completion () |
| void | handleLaser (sensor_msgs::LaserScan msg) |
| callback function handling the LaserScan messages | |
Private Attributes | |
| nlj_laser::LaserDescriptor | actual_trajectory_descriptor_ |
| actual trajectory descriptor holds all the laser scans in a array | |
| bool | assigned_ |
| if assigned is true, robot have a goal to navigate towards | |
| ros::Publisher | cmd_vel_publisher_ |
| publisher to provide cmd_vel command | |
| bool | completed_ |
| std::string | get_service_name_ |
| ros::Subscriber | laser_scan_subscriber_ |
| keep the subscriber to allow subscribe/un-subscribe as start/stop/interrupt/continue is called | |
| const double | max_traversing_delta_ |
| const double | mean_traversing_time_ |
| int | navigation_index_ |
| index of reference scan which robot use for localize itself and navigate towards it | |
| sensor_msgs::LaserScan | reference_laser_scan_ |
| reference scan | |
Definition at line 15 of file nj_laser.h.
| NJLaser::NJLaser | ( | const std::string & | name, |
| const std::string & | get_service_name | ||
| ) |
Definition at line 3 of file nj_laser.cpp.
| double NJLaser::completion | ( | ) | [private] |
Definition at line 148 of file nj_laser.cpp.
| void NJLaser::handleLaser | ( | sensor_msgs::LaserScan | msg | ) | [private] |
callback function handling the LaserScan messages
Definition at line 90 of file nj_laser.cpp.
| void NJLaser::onContinue | ( | ) | [virtual] |
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 84 of file nj_laser.cpp.
| void NJLaser::onInterrupt | ( | ) | [virtual] |
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 79 of file nj_laser.cpp.
| void NJLaser::onStop | ( | ) | [virtual] |
Implements lama_jockeys::NavigatingJockey.
Definition at line 11 of file nj_laser.cpp.
| void NJLaser::onTraverse | ( | ) | [virtual] |
Implements lama_jockeys::NavigatingJockey.
Definition at line 22 of file nj_laser.cpp.
nlj_laser::LaserDescriptor NJLaser::actual_trajectory_descriptor_ [private] |
actual trajectory descriptor holds all the laser scans in a array
Definition at line 36 of file nj_laser.h.
bool NJLaser::assigned_ [private] |
if assigned is true, robot have a goal to navigate towards
Definition at line 38 of file nj_laser.h.
ros::Publisher NJLaser::cmd_vel_publisher_ [private] |
publisher to provide cmd_vel command
Definition at line 32 of file nj_laser.h.
bool NJLaser::completed_ [private] |
Definition at line 42 of file nj_laser.h.
std::string NJLaser::get_service_name_ [private] |
Definition at line 29 of file nj_laser.h.
keep the subscriber to allow subscribe/un-subscribe as start/stop/interrupt/continue is called
Definition at line 31 of file nj_laser.h.
const double NJLaser::max_traversing_delta_ [private] |
Definition at line 35 of file nj_laser.h.
const double NJLaser::mean_traversing_time_ [private] |
Definition at line 34 of file nj_laser.h.
int NJLaser::navigation_index_ [private] |
index of reference scan which robot use for localize itself and navigate towards it
Definition at line 39 of file nj_laser.h.
sensor_msgs::LaserScan NJLaser::reference_laser_scan_ [private] |
reference scan
Definition at line 40 of file nj_laser.h.