1 #ifndef ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED 2 #define ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED 16 #include <rostate_machine/State.h> 17 #include <rostate_machine/Event.h> 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> 44 const std::string
tag;
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) {}
56 void registerCallback(std::function<boost::optional<rostate_machine::Event>(
void)> func,std::string
tag);
57 void publishEvent(rostate_machine::Event event);
60 boost::optional<rostate_machine::State> getCurrentState();
61 boost::optional<rostate_machine::State> getPreviousState();
65 trigger_event_pub_.publish(event);
73 void stateCallback(
const rostate_machine::State::ConstPtr msg);
74 boost::circular_buffer<rostate_machine::State>
state_buf_;
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_;
82 bool eventKeyFound(rostate_machine::Event event);
87 #endif //ROSTATE_MACHINE_EVENT_CLIENT_H_INCLUDED ros::Subscriber current_state_sub_
TagInfo(std::string tag, int when, std::vector< std::string > states)
ros::Publisher trigger_event_pub_
std::vector< std::string > available_events_
const std::string client_namespace
void setEvent(rostate_machine::Event event)
const std::vector< std::string > states
std::vector< TagInfo > tag_info_
boost::circular_buffer< rostate_machine::State > state_buf_
ros::Time state_changed_timestamp_