00001 00009 /***************************************************************************** 00010 ** Ifdefs 00011 *****************************************************************************/ 00012 00013 #ifndef CMD_VEL_SUBSCRIBERS_HPP_ 00014 #define CMD_VEL_SUBSCRIBERS_HPP_ 00015 00016 /***************************************************************************** 00017 ** Includes 00018 *****************************************************************************/ 00019 00020 #include <ros/ros.h> 00021 #include <geometry_msgs/Twist.h> 00022 #include <yaml-cpp/yaml.h> 00023 00024 /***************************************************************************** 00025 ** Preprocessing 00026 *****************************************************************************/ 00027 00028 // move to a static const? 00029 #define VACANT std::numeric_limits<unsigned int>::max() 00030 00031 /***************************************************************************** 00032 ** Namespaces 00033 *****************************************************************************/ 00034 00035 namespace cmd_vel_mux { 00036 00037 /***************************************************************************** 00038 ** CmdVelSubscribers 00039 *****************************************************************************/ 00040 00044 class CmdVelSubscribers 00045 { 00046 public: 00047 00051 class CmdVelSubs 00052 { 00053 public: 00054 unsigned int idx; 00055 std::string name; 00056 ros::Subscriber subs; 00057 std::string topic; 00058 ros::Timer timer; 00059 double timeout; 00060 unsigned int priority; 00061 std::string short_desc; 00062 bool active; 00064 CmdVelSubs(unsigned int idx) : idx(idx), active(false) {}; 00065 00066 void operator << (const YAML::Node& node); 00067 }; 00068 00069 CmdVelSubscribers() : allowed(VACANT) { } 00070 ~CmdVelSubscribers() { } 00071 00072 std::vector<CmdVelSubs>::size_type size() { return list.size(); }; 00073 CmdVelSubs& operator [] (unsigned int idx) { return list[idx]; }; 00074 00083 void configure(const YAML::Node& node); 00084 00085 unsigned int allowed; 00086 00087 private: 00088 std::vector<CmdVelSubs> list; 00089 }; 00090 00091 } // namespace cmd_vel_mux 00092 00093 #endif /* CMD_VEL_SUBSCRIBERS_HPP_ */