event_client.h
Go to the documentation of this file.
1 #ifndef ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED
2 #define ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED
3 
15 // Headers in this package
16 #include <rostate_machine/State.h>
17 #include <rostate_machine/Event.h>
18 
19 // Headers in ROS
20 #include <ros/ros.h>
21 
22 // Headers in Boost
23 #include <boost/circular_buffer.hpp>
24 #include <boost/optional.hpp>
25 #include <boost/graph/adjacency_list.hpp>
26 #include <boost/graph/graph_utility.hpp>
27 #include <boost/property_tree/ptree.hpp>
28 #include <boost/property_tree/xml_parser.hpp>
29 #include <boost/foreach.hpp>
30 #include <boost/lexical_cast.hpp>
31 
32 // Headers in STL
33 #include <vector>
34 #include <map>
35 
36 namespace rostate_machine
37 {
38  constexpr int always = 0;
39  constexpr int on_entry = 1;
40  constexpr int on_exit = 2;
41 
42  struct TagInfo
43  {
44  const std::string tag;
45  const int when;
46  const std::vector<std::string> states;
47  TagInfo(std::string tag,int when,std::vector<std::string> states)
48  : tag(tag),when(when),states(states) {}
49  };
50 
52  {
53  public:
54  EventClient(ros::NodeHandle nh,ros::NodeHandle pnh,std::string client_namespace);
55  ~EventClient();
56  void registerCallback(std::function<boost::optional<rostate_machine::Event>(void)> func,std::string tag);
57  void publishEvent(rostate_machine::Event event);
58  void run();
59  const std::string client_namespace;
60  boost::optional<rostate_machine::State> getCurrentState();
61  boost::optional<rostate_machine::State> getPreviousState();
62  ros::Duration getCurrentStateDuration();
63  void setEvent(rostate_machine::Event event)
64  {
65  trigger_event_pub_.publish(event);
66  return;
67  };
68  private:
73  void stateCallback(const rostate_machine::State::ConstPtr msg);
74  boost::circular_buffer<rostate_machine::State> state_buf_;
75  std::string description_;
76  void loadXml();
77  std::vector<std::string> onTransition();
78  std::vector<std::string> split(const std::string &s, char delim);
79  std::map<std::string, std::vector<std::function<boost::optional<rostate_machine::Event>(void)> > > tagged_functions_;
80  std::vector<TagInfo> tag_info_;
81  std::vector<std::string> available_events_;
82  bool eventKeyFound(rostate_machine::Event event);
84  };
85 }
86 
87 #endif //ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED
ros::Subscriber current_state_sub_
Definition: event_client.h:72
TagInfo(std::string tag, int when, std::vector< std::string > states)
Definition: event_client.h:47
ros::Publisher trigger_event_pub_
Definition: event_client.h:71
std::vector< std::string > available_events_
Definition: event_client.h:81
const std::string client_namespace
Definition: event_client.h:59
constexpr int on_exit
Definition: event_client.h:40
constexpr int on_entry
Definition: event_client.h:39
constexpr int always
Definition: event_client.h:38
void setEvent(rostate_machine::Event event)
Definition: event_client.h:63
const std::vector< std::string > states
Definition: event_client.h:46
std::vector< TagInfo > tag_info_
Definition: event_client.h:80
const std::string tag
Definition: event_client.h:44
boost::circular_buffer< rostate_machine::State > state_buf_
Definition: event_client.h:74


rostate_machine
Author(s):
autogenerated on Wed Sep 4 2019 05:19:52