13 #ifndef YUJIN_OCS_CMD_VEL_MUX_HPP_    14 #define YUJIN_OCS_CMD_VEL_MUX_HPP_    22 #include <dynamic_reconfigure/server.h>    24 #include "yocs_cmd_vel_mux/reloadConfig.h"    55   static const unsigned int VACANT       = 666666;  
    66   void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& msg, 
unsigned int idx);
    91     void operator()(
const geometry_msgs::Twist::ConstPtr& msg)
 
ros::Publisher active_subscriber
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig >::CallbackType dynamic_reconfigure_cb
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig > * dynamic_reconfigure_server
CmdVelSubscribers cmd_vel_subs
static const unsigned int VACANT
CmdVelFunctor(unsigned int idx, CmdVelMuxNodelet *node)
Structure for the cmd_vel_mux. 
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &msg, unsigned int idx)
std::string output_topic_name
TimerFunctor(unsigned int idx, CmdVelMuxNodelet *node)
void operator()(const geometry_msgs::Twist::ConstPtr &msg)
double common_timer_period
void reloadConfiguration(yocs_cmd_vel_mux::reloadConfig &config, uint32_t unused_level)
static const unsigned int GLOBAL_TIMER
ros::Publisher output_topic_pub
void operator()(const ros::TimerEvent &event)
void timerCallback(const ros::TimerEvent &event, unsigned int idx)