00001 00009 /***************************************************************************** 00010 ** Ifdefs 00011 *****************************************************************************/ 00012 00013 #ifndef YUJIN_OCS_CMD_VEL_MUX_HPP_ 00014 #define YUJIN_OCS_CMD_VEL_MUX_HPP_ 00015 00016 /***************************************************************************** 00017 ** Includes 00018 *****************************************************************************/ 00019 00020 #include <ros/ros.h> 00021 #include <nodelet/nodelet.h> 00022 #include <dynamic_reconfigure/server.h> 00023 00024 #include "cmd_vel_mux/reloadConfig.h" 00025 #include "cmd_vel_mux/cmd_vel_subscribers.hpp" 00026 00027 /***************************************************************************** 00028 ** Namespaces 00029 *****************************************************************************/ 00030 00031 namespace cmd_vel_mux { 00032 00033 /***************************************************************************** 00034 ** CmdVelMux 00035 *****************************************************************************/ 00036 00037 class CmdVelMuxNodelet : public nodelet::Nodelet 00038 { 00039 public: 00040 virtual void onInit(); 00041 00042 CmdVelMuxNodelet() 00043 { 00044 dynamic_reconfigure_server = NULL; 00045 } 00046 00047 ~CmdVelMuxNodelet() 00048 { 00049 if (dynamic_reconfigure_server != NULL) 00050 delete dynamic_reconfigure_server; 00051 } 00052 00053 private: 00054 CmdVelSubscribers cmd_vel_sub; 00055 ros::Publisher mux_cmd_vel_pub; 00056 ros::Publisher active_subscriber; 00058 void timerCallback(const ros::TimerEvent& event, unsigned int idx); 00059 void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& msg, unsigned int idx); 00060 00061 /********************* 00062 ** Dynamic Reconfigure 00063 **********************/ 00064 dynamic_reconfigure::Server<cmd_vel_mux::reloadConfig> * dynamic_reconfigure_server; 00065 dynamic_reconfigure::Server<cmd_vel_mux::reloadConfig>::CallbackType dynamic_reconfigure_cb; 00066 void reloadConfiguration(cmd_vel_mux::reloadConfig &config, uint32_t unused_level); 00067 00068 /********************* 00069 ** Private Classes 00070 **********************/ 00071 // Functor assigned to each incoming velocity topic to bind it to cmd_vel callback 00072 class CmdVelFunctor 00073 { 00074 private: 00075 unsigned int idx; 00076 CmdVelMuxNodelet* node; 00077 00078 public: 00079 CmdVelFunctor(unsigned int idx, CmdVelMuxNodelet* node) : 00080 idx(idx), node(node) 00081 { 00082 } 00083 00084 void operator()(const geometry_msgs::Twist::ConstPtr& msg) 00085 { 00086 node->cmdVelCallback(msg, idx); 00087 } 00088 }; 00089 00090 // Functor assigned to each velocity messages source to bind it to timer callback 00091 class TimerFunctor 00092 { 00093 private: 00094 unsigned int idx; 00095 CmdVelMuxNodelet* node; 00096 00097 public: 00098 TimerFunctor(unsigned int idx, CmdVelMuxNodelet* node) : 00099 idx(idx), node(node) 00100 { 00101 } 00102 00103 void operator()(const ros::TimerEvent& event) 00104 { 00105 node->timerCallback(event, idx); 00106 } 00107 }; 00108 }; 00109 00110 } // namespace cmd_vel_mux 00111 00112 #endif /* YUJIN_OCS_CMD_VEL_MUX_HPP_ */