cmd_vel_mux_nodelet.hpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Ifdefs
11  *****************************************************************************/
12 
13 #ifndef YUJIN_OCS_CMD_VEL_MUX_HPP_
14 #define YUJIN_OCS_CMD_VEL_MUX_HPP_
15 
16 /*****************************************************************************
17  ** Includes
18  *****************************************************************************/
19 
20 #include <ros/ros.h>
21 #include <nodelet/nodelet.h>
22 #include <dynamic_reconfigure/server.h>
23 
24 #include "yocs_cmd_vel_mux/reloadConfig.h"
26 
27 /*****************************************************************************
28 ** Namespaces
29 *****************************************************************************/
30 
31 namespace yocs_cmd_vel_mux {
32 
33 /*****************************************************************************
34  ** CmdVelMux
35  *****************************************************************************/
36 
38 {
39 public:
40  virtual void onInit();
41 
43  {
46  }
47 
49  {
50  if (dynamic_reconfigure_server != NULL)
52  }
53 
54 private:
55  static const unsigned int VACANT = 666666;
56  static const unsigned int GLOBAL_TIMER = 888888;
60  std::string output_topic_name;
65  void timerCallback(const ros::TimerEvent& event, unsigned int idx);
66  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& msg, unsigned int idx);
67 
68  /*********************
69  ** Dynamic Reconfigure
70  **********************/
71  dynamic_reconfigure::Server<yocs_cmd_vel_mux::reloadConfig> * dynamic_reconfigure_server;
72  dynamic_reconfigure::Server<yocs_cmd_vel_mux::reloadConfig>::CallbackType dynamic_reconfigure_cb;
73  void reloadConfiguration(yocs_cmd_vel_mux::reloadConfig &config, uint32_t unused_level);
74 
75  /*********************
76  ** Private Classes
77  **********************/
78  // Functor assigned to each incoming velocity topic to bind it to cmd_vel callback
80  {
81  private:
82  unsigned int idx;
84 
85  public:
86  CmdVelFunctor(unsigned int idx, CmdVelMuxNodelet* node) :
87  idx(idx), node(node)
88  {
89  }
90 
91  void operator()(const geometry_msgs::Twist::ConstPtr& msg)
92  {
93  node->cmdVelCallback(msg, idx);
94  }
95  };
96 
97  // Functor assigned to each velocity messages source to bind it to timer callback
99  {
100  private:
101  unsigned int idx;
103 
104  public:
105  TimerFunctor(unsigned int idx, CmdVelMuxNodelet* node) :
106  idx(idx), node(node)
107  {
108  }
109 
110  void operator()(const ros::TimerEvent& event)
111  {
112  node->timerCallback(event, idx);
113  }
114  };
115 };
116 
117 } // namespace yocs_cmd_vel_mux
118 
119 #endif /* YUJIN_OCS_CMD_VEL_MUX_HPP_ */
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig >::CallbackType dynamic_reconfigure_cb
dynamic_reconfigure::Server< yocs_cmd_vel_mux::reloadConfig > * dynamic_reconfigure_server
CmdVelFunctor(unsigned int idx, CmdVelMuxNodelet *node)
Structure for the cmd_vel_mux.
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &msg, unsigned int idx)
TimerFunctor(unsigned int idx, CmdVelMuxNodelet *node)
void operator()(const geometry_msgs::Twist::ConstPtr &msg)
void reloadConfiguration(yocs_cmd_vel_mux::reloadConfig &config, uint32_t unused_level)
static const unsigned int GLOBAL_TIMER
void timerCallback(const ros::TimerEvent &event, unsigned int idx)


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