Public Member Functions | Public Attributes | List of all members
yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs Class Reference

#include <cmd_vel_subscribers.hpp>

Public Member Functions

 CmdVelSubs (unsigned int idx)
 
void operator<< (const YAML::Node &node)
 
 ~CmdVelSubs ()
 

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
 

Detailed Description

Inner class describing an individual subscriber to a cmd_vel topic

Definition at line 57 of file cmd_vel_subscribers.hpp.

Constructor & Destructor Documentation

yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::CmdVelSubs ( unsigned int  idx)
inline

Definition at line 70 of file cmd_vel_subscribers.hpp.

yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::~CmdVelSubs ( )
inline

Definition at line 71 of file cmd_vel_subscribers.hpp.

Member Function Documentation

void yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::operator<< ( const YAML::Node &  node)

Fill attributes with a YAML node content

Definition at line 28 of file cmd_vel_subscribers.cpp.

Member Data Documentation

bool yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::active

Whether this source is active

Definition at line 68 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 60 of file cmd_vel_subscribers.hpp.

std::string yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::name

Descriptive name; must be unique to this subscriber

Definition at line 61 of file cmd_vel_subscribers.hpp.

unsigned int yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::priority

UNIQUE integer from 0 (lowest priority) to MAX_INT

Definition at line 66 of file cmd_vel_subscribers.hpp.

std::string yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::short_desc

Short description (optional)

Definition at line 67 of file cmd_vel_subscribers.hpp.

ros::Subscriber yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::subs

The subscriber itself

Definition at line 63 of file cmd_vel_subscribers.hpp.

double yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::timeout

Timer's timeout, in seconds

Definition at line 65 of file cmd_vel_subscribers.hpp.

ros::Timer yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::timer

No incoming messages timeout

Definition at line 64 of file cmd_vel_subscribers.hpp.

std::string yocs_cmd_vel_mux::CmdVelSubscribers::CmdVelSubs::topic

The name of the topic

Definition at line 62 of file cmd_vel_subscribers.hpp.


The documentation for this class was generated from the following files:


yocs_cmd_vel_mux
Author(s): Jorge Santos Simon
autogenerated on Mon Jun 10 2019 15:53:29