cmd_vel_subscribers.hpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10 ** Ifdefs
11 *****************************************************************************/
12 
13 #ifndef YUJIN_OCS_CMD_VEL_SUBSCRIBERS_HPP_
14 #define YUJIN_OCS_CMD_VEL_SUBSCRIBERS_HPP_
15 
16 /*****************************************************************************
17 ** Includes
18 *****************************************************************************/
19 
20 #include <ros/ros.h>
21 #include <geometry_msgs/Twist.h>
22 
23 #include <yaml-cpp/yaml.h>
24 
25 #ifdef HAVE_NEW_YAMLCPP
26 // The >> operator disappeared in yaml-cpp 0.5, so this function is
27 // added to provide support for code written under the yaml-cpp 0.3 API.
28 template<typename T>
29 void operator >> (const YAML::Node& node, T& i)
30 {
31  i = node.as<T>();
32 }
33 #endif
34 
35 
36 /*****************************************************************************
37 ** Namespaces
38 *****************************************************************************/
39 
40 namespace yocs_cmd_vel_mux {
41 
42 
43 /*****************************************************************************
44 ** CmdVelSubscribers
45 *****************************************************************************/
46 
51 {
52 public:
53 
57  class CmdVelSubs
58  {
59  public:
60  unsigned int idx;
61  std::string name;
62  std::string topic;
65  double timeout;
66  unsigned int priority;
67  std::string short_desc;
68  bool active;
70  CmdVelSubs(unsigned int idx) : idx(idx), active(false) { };
72 
74  void operator << (const YAML::Node& node);
75  };
76 
79 
80  std::vector<std::shared_ptr<CmdVelSubs>>::size_type size() { return list.size(); };
81  std::shared_ptr<CmdVelSubs>& operator [] (unsigned int idx) { return list[idx]; };
82 
91  void configure(const YAML::Node& node);
92 
93  unsigned int allowed;
94 
95 private:
96  std::vector<std::shared_ptr<CmdVelSubs>> list;
97 };
98 
99 } // namespace yocs_cmd_vel_mux
100 
101 
102 #endif /* CMD_VEL_SUBSCRIBERS_HPP_ */
void configure(const YAML::Node &node)
Configures the subscribers from a yaml file.
std::vector< std::shared_ptr< CmdVelSubs > > list
std::vector< std::shared_ptr< CmdVelSubs > >::size_type size()
std::shared_ptr< CmdVelSubs > & operator[](unsigned int idx)


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