#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) |
Public Member Functions inherited from Mode | |
bool | finished () |
color::rgba | getActualColor () |
color::rgba | getColor () |
double | getFrequency () |
int | getPriority () |
int | getPulses () |
double | getTimeout () |
bool | isRunning () |
Mode (int priority=0, double freq=0, int pulses=0, double timeout=0) | |
void | pause () |
int | pulsed () |
void | setActualColor (color::rgba color) |
void | setColor (color::rgba color) |
void | setFrequency (double freq) |
void | setPriority (int priority) |
void | setPulses (int pulses) |
void | setTimeout (double timeout) |
boost::signals2::signal< void(color::rgba color)> * | signalColorReady () |
boost::signals2::signal< void(std::vector< color::rgba > &colors)> * | signalColorsReady () |
boost::signals2::signal< void(int)> * | signalModeFinished () |
void | start () |
void | stop () |
virtual | ~Mode () |
Static Public Attributes | |
static constexpr float | DIST_MAX = 2.0f |
static constexpr float | DIST_MIN = 0.3f |
static constexpr 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 |
Additional Inherited Members | |
Protected Member Functions inherited from Mode | |
virtual void | run () |
Protected Attributes inherited from Mode | |
color::rgba | _actualColor |
color::rgba | _color |
std::vector< color::rgba > | _colors |
bool | _finished |
double | _freq |
color::rgba | _init_color |
int | _priority |
int | _pulsed |
int | _pulses |
double | _timeout |
boost::signals2::signal< void(color::rgba color)> | m_sigColorReady |
boost::signals2::signal< void(std::vector< color::rgba > &colors)> | m_sigColorsReady |
boost::signals2::signal< void(int)> | m_sigFinished |
Static Protected Attributes inherited from Mode | |
static const unsigned int | UPDATE_RATE_HZ = 100 |
Definition at line 32 of file distApproxMode.h.
|
inline |
Definition at line 35 of file distApproxMode.h.
|
inlinevirtual |
Implements Mode.
Definition at line 57 of file distApproxMode.h.
|
inlinevirtual |
Implements Mode.
Definition at line 116 of file distApproxMode.h.
|
inline |
Definition at line 51 of file distApproxMode.h.
|
private |
Definition at line 124 of file distApproxMode.h.
|
private |
Definition at line 125 of file distApproxMode.h.
|
private |
Definition at line 123 of file distApproxMode.h.
|
private |
Definition at line 134 of file distApproxMode.h.
|
private |
Definition at line 132 of file distApproxMode.h.
|
private |
Definition at line 133 of file distApproxMode.h.
|
private |
Definition at line 131 of file distApproxMode.h.
|
static |
Definition at line 119 of file distApproxMode.h.
|
static |
Definition at line 118 of file distApproxMode.h.
|
private |
Definition at line 130 of file distApproxMode.h.
|
private |
Definition at line 127 of file distApproxMode.h.
|
private |
Definition at line 129 of file distApproxMode.h.
|
static |
Definition at line 120 of file distApproxMode.h.