35 #ifndef ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
36 #define ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
39 #include <actionlib_msgs/GoalStatusArray.h>
43 #include <boost/thread/condition.hpp>
44 #include <boost/thread/recursive_mutex.hpp>
66 void processStatus(
const actionlib_msgs::GoalStatusArrayConstPtr & status,
67 const std::string & cur_status_caller_id);
71 bool isServerConnected();
75 std::string status_caller_id_;
76 bool status_received_;
79 boost::condition check_connection_condition_;
81 boost::recursive_mutex data_mutex_;
82 std::map<std::string, size_t> goalSubscribers_;
83 std::map<std::string, size_t> cancelSubscribers_;
85 std::string goalSubscribersString();
86 std::string cancelSubscribersString();
94 #endif // ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_