Classes | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
yocs_cmd_vel_mux::CmdVelMuxNodelet Class Reference

#include <cmd_vel_mux_nodelet.hpp>

Inheritance diagram for yocs_cmd_vel_mux::CmdVelMuxNodelet:
Inheritance graph
[legend]

Classes

class  CmdVelFunctor
 
class  TimerFunctor
 

Public Member Functions

 CmdVelMuxNodelet ()
 
virtual void onInit ()
 
 ~CmdVelMuxNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void cmdVelCallback (const geometry_msgs::Twist::ConstPtr &msg, unsigned int idx)
 
void reloadConfiguration (yocs_cmd_vel_mux::reloadConfig &config, uint32_t unused_level)
 
void timerCallback (const ros::TimerEvent &event, unsigned int idx)
 

Private Attributes

ros::Publisher active_subscriber
 
CmdVelSubscribers cmd_vel_subs
 
ros::Timer common_timer
 
double common_timer_period
 
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig >::CallbackType dynamic_reconfigure_cb
 
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig > * dynamic_reconfigure_server
 
std::string output_topic_name
 
ros::Publisher output_topic_pub
 

Static Private Attributes

static const unsigned int GLOBAL_TIMER = 888888
 
static const unsigned int VACANT = 666666
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 37 of file cmd_vel_mux_nodelet.hpp.

Constructor & Destructor Documentation

yocs_cmd_vel_mux::CmdVelMuxNodelet::CmdVelMuxNodelet ( )
inline

Definition at line 42 of file cmd_vel_mux_nodelet.hpp.

yocs_cmd_vel_mux::CmdVelMuxNodelet::~CmdVelMuxNodelet ( )
inline

Definition at line 48 of file cmd_vel_mux_nodelet.hpp.

Member Function Documentation

void yocs_cmd_vel_mux::CmdVelMuxNodelet::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr &  msg,
unsigned int  idx 
)
private

Definition at line 30 of file cmd_vel_mux_nodelet.cpp.

void yocs_cmd_vel_mux::CmdVelMuxNodelet::onInit ( )
virtual

Implements nodelet::Nodelet.

Definition at line 88 of file cmd_vel_mux_nodelet.cpp.

void yocs_cmd_vel_mux::CmdVelMuxNodelet::reloadConfiguration ( yocs_cmd_vel_mux::reloadConfig &  config,
uint32_t  unused_level 
)
private

Definition at line 110 of file cmd_vel_mux_nodelet.cpp.

void yocs_cmd_vel_mux::CmdVelMuxNodelet::timerCallback ( const ros::TimerEvent event,
unsigned int  idx 
)
private

Definition at line 62 of file cmd_vel_mux_nodelet.cpp.

Member Data Documentation

ros::Publisher yocs_cmd_vel_mux::CmdVelMuxNodelet::active_subscriber
private

Currently allowed cmd_vel subscriber

Definition at line 61 of file cmd_vel_mux_nodelet.hpp.

CmdVelSubscribers yocs_cmd_vel_mux::CmdVelMuxNodelet::cmd_vel_subs
private

Pool of cmd_vel topics subscribers

Definition at line 58 of file cmd_vel_mux_nodelet.hpp.

ros::Timer yocs_cmd_vel_mux::CmdVelMuxNodelet::common_timer
private

No messages from any subscriber timeout

Definition at line 62 of file cmd_vel_mux_nodelet.hpp.

double yocs_cmd_vel_mux::CmdVelMuxNodelet::common_timer_period
private

No messages from any subscriber timeout period

Definition at line 63 of file cmd_vel_mux_nodelet.hpp.

dynamic_reconfigure::Server<yocs_cmd_vel_mux::reloadConfig>::CallbackType yocs_cmd_vel_mux::CmdVelMuxNodelet::dynamic_reconfigure_cb
private

Definition at line 72 of file cmd_vel_mux_nodelet.hpp.

dynamic_reconfigure::Server<yocs_cmd_vel_mux::reloadConfig>* yocs_cmd_vel_mux::CmdVelMuxNodelet::dynamic_reconfigure_server
private

Definition at line 71 of file cmd_vel_mux_nodelet.hpp.

const unsigned int yocs_cmd_vel_mux::CmdVelMuxNodelet::GLOBAL_TIMER = 888888
staticprivate

ID for the global timer functor; anything big is ok

Definition at line 56 of file cmd_vel_mux_nodelet.hpp.

std::string yocs_cmd_vel_mux::CmdVelMuxNodelet::output_topic_name
private

Multiplexed command velocity topic name

Definition at line 60 of file cmd_vel_mux_nodelet.hpp.

ros::Publisher yocs_cmd_vel_mux::CmdVelMuxNodelet::output_topic_pub
private

Multiplexed command velocity topic

Definition at line 59 of file cmd_vel_mux_nodelet.hpp.

const unsigned int yocs_cmd_vel_mux::CmdVelMuxNodelet::VACANT = 666666
staticprivate

ID for "nobody" active input; anything big is ok

Definition at line 55 of file cmd_vel_mux_nodelet.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