#include <cmd_vel_subscribers.hpp>
Public Member Functions | |
CmdVelSubs (unsigned int idx) | |
void | operator<< (const YAML::Node &node) |
Public Attributes | |
bool | active |
unsigned int | idx |
std::string | name |
unsigned int | priority |
std::string | short_desc |
ros::Subscriber | subs |
double | timeout |
ros::Timer | timer |
std::string | topic |
Inner class describing an individual subscriber to a cmd_vel topic
Definition at line 61 of file cmd_vel_subscribers.hpp.
yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::CmdVelSubs | ( | unsigned int | idx | ) | [inline] |
Definition at line 74 of file cmd_vel_subscribers.hpp.
void yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::operator<< | ( | const YAML::Node & | node | ) |
Definition at line 28 of file cmd_vel_subscribers.cpp.
Whether this source is active
Definition at line 72 of file cmd_vel_subscribers.hpp.
unsigned int yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::idx |
Index; assigned according to the order on YAML file
Definition at line 64 of file cmd_vel_subscribers.hpp.
Descriptive name
Definition at line 65 of file cmd_vel_subscribers.hpp.
UNIQUE integer from 0 (lowest priority) to MAX_INT
Definition at line 70 of file cmd_vel_subscribers.hpp.
Short description (optional)
Definition at line 71 of file cmd_vel_subscribers.hpp.
The subscriber itself
Definition at line 66 of file cmd_vel_subscribers.hpp.
Timer's timeout, in seconds
Definition at line 69 of file cmd_vel_subscribers.hpp.
No incoming messages timeout
Definition at line 68 of file cmd_vel_subscribers.hpp.
The name of the topic
Definition at line 67 of file cmd_vel_subscribers.hpp.