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();
85 std::string goalSubscribersString();
86 std::string cancelSubscribersString();
94 #endif // ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
std::map< std::string, size_t > goalSubscribers_
boost::recursive_mutex data_mutex_
std::map< std::string, size_t > cancelSubscribers_
ros::Subscriber & result_sub_
ros::Time latest_status_time_
boost::condition check_connection_condition_
ros::Subscriber & feedback_sub_
std::string status_caller_id_