#include <distApproxMode.h>
Public Member Functions | |
DistApproxMode (size_t num_leds, int priority=0, double freq=5, int pulses=0, double timeout=0) | |
void | execute () |
std::string | getName () |
void | scan_callback (const sensor_msgs::LaserScanConstPtr &msg) |
Static Public Attributes | |
static const float | DIST_MAX = 2.0f |
static const float | DIST_MIN = 0.3f |
static const double | UPDATE_FREQ = 50.0 |
Private Attributes | |
double | _inc |
size_t | _num_leds |
double | _timer_inc |
color::rgba | c_default |
color::rgba | c_green |
color::rgba | c_off |
color::rgba | c_red |
boost::mutex | mutex |
sensor_msgs::LaserScan | scan |
ros::Subscriber | sub_scan |
Definition at line 32 of file distApproxMode.h.
DistApproxMode::DistApproxMode | ( | size_t | num_leds, |
int | priority = 0 , |
||
double | freq = 5 , |
||
int | pulses = 0 , |
||
double | timeout = 0 |
||
) | [inline] |
Definition at line 35 of file distApproxMode.h.
void DistApproxMode::execute | ( | ) | [inline, virtual] |
Implements Mode.
Definition at line 57 of file distApproxMode.h.
std::string DistApproxMode::getName | ( | ) | [inline, virtual] |
Implements Mode.
Definition at line 116 of file distApproxMode.h.
void DistApproxMode::scan_callback | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) | [inline] |
Definition at line 51 of file distApproxMode.h.
double DistApproxMode::_inc [private] |
Definition at line 124 of file distApproxMode.h.
size_t DistApproxMode::_num_leds [private] |
Definition at line 125 of file distApproxMode.h.
double DistApproxMode::_timer_inc [private] |
Definition at line 123 of file distApproxMode.h.
color::rgba DistApproxMode::c_default [private] |
Definition at line 134 of file distApproxMode.h.
color::rgba DistApproxMode::c_green [private] |
Definition at line 132 of file distApproxMode.h.
color::rgba DistApproxMode::c_off [private] |
Definition at line 133 of file distApproxMode.h.
color::rgba DistApproxMode::c_red [private] |
Definition at line 131 of file distApproxMode.h.
const float DistApproxMode::DIST_MAX = 2.0f [static] |
Definition at line 119 of file distApproxMode.h.
const float DistApproxMode::DIST_MIN = 0.3f [static] |
Definition at line 118 of file distApproxMode.h.
boost::mutex DistApproxMode::mutex [private] |
Definition at line 130 of file distApproxMode.h.
sensor_msgs::LaserScan DistApproxMode::scan [private] |
Definition at line 127 of file distApproxMode.h.
ros::Subscriber DistApproxMode::sub_scan [private] |
Definition at line 129 of file distApproxMode.h.
const double DistApproxMode::UPDATE_FREQ = 50.0 [static] |
Definition at line 120 of file distApproxMode.h.