#include <connection_monitor.h>
Public Member Functions | |
void | cancelConnectCallback (const ros::SingleSubscriberPublisher &pub) |
void | cancelDisconnectCallback (const ros::SingleSubscriberPublisher &pub) |
ConnectionMonitor (ros::Subscriber &feedback_sub, ros::Subscriber &result_sub) | |
void | goalConnectCallback (const ros::SingleSubscriberPublisher &pub) |
void | goalDisconnectCallback (const ros::SingleSubscriberPublisher &pub) |
bool | isServerConnected () |
void | processStatus (const actionlib_msgs::GoalStatusArrayConstPtr &status) |
bool | waitForActionServerToStart (const ros::Duration &timeout=ros::Duration(0, 0), const ros::NodeHandle &nh=ros::NodeHandle()) |
Private Member Functions | |
std::string | cancelSubscribersString () |
std::string | goalSubscribersString () |
Private Attributes | |
std::set< std::string > | cancelSubscribers_ |
boost::condition | check_connection_condition_ |
boost::recursive_mutex | data_mutex_ |
ros::Subscriber & | feedback_sub_ |
std::set< std::string > | goalSubscribers_ |
ros::Time | latest_status_time_ |
ros::Subscriber & | result_sub_ |
std::string | status_caller_id_ |
bool | status_received_ |
Definition at line 49 of file connection_monitor.h.
ConnectionMonitor::ConnectionMonitor | ( | ros::Subscriber & | feedback_sub, | |
ros::Subscriber & | result_sub | |||
) |
Definition at line 51 of file connection_monitor.cpp.
void ConnectionMonitor::cancelConnectCallback | ( | const ros::SingleSubscriberPublisher & | pub | ) |
Definition at line 105 of file connection_monitor.cpp.
void ConnectionMonitor::cancelDisconnectCallback | ( | const ros::SingleSubscriberPublisher & | pub | ) |
Definition at line 122 of file connection_monitor.cpp.
string ConnectionMonitor::cancelSubscribersString | ( | ) | [private] |
Definition at line 139 of file connection_monitor.cpp.
void ConnectionMonitor::goalConnectCallback | ( | const ros::SingleSubscriberPublisher & | pub | ) |
Definition at line 59 of file connection_monitor.cpp.
void ConnectionMonitor::goalDisconnectCallback | ( | const ros::SingleSubscriberPublisher & | pub | ) |
Definition at line 76 of file connection_monitor.cpp.
string ConnectionMonitor::goalSubscribersString | ( | ) | [private] |
Definition at line 93 of file connection_monitor.cpp.
bool ConnectionMonitor::isServerConnected | ( | ) |
Definition at line 179 of file connection_monitor.cpp.
void ConnectionMonitor::processStatus | ( | const actionlib_msgs::GoalStatusArrayConstPtr & | status | ) |
Definition at line 151 of file connection_monitor.cpp.
bool ConnectionMonitor::waitForActionServerToStart | ( | const ros::Duration & | timeout = ros::Duration(0,0) , |
|
const ros::NodeHandle & | nh = ros::NodeHandle() | |||
) |
Definition at line 219 of file connection_monitor.cpp.
std::set<std::string> actionlib::ConnectionMonitor::cancelSubscribers_ [private] |
Definition at line 78 of file connection_monitor.h.
boost::condition actionlib::ConnectionMonitor::check_connection_condition_ [private] |
Definition at line 74 of file connection_monitor.h.
boost::recursive_mutex actionlib::ConnectionMonitor::data_mutex_ [private] |
Definition at line 76 of file connection_monitor.h.
ros::Subscriber& actionlib::ConnectionMonitor::feedback_sub_ [private] |
Definition at line 83 of file connection_monitor.h.
std::set<std::string> actionlib::ConnectionMonitor::goalSubscribers_ [private] |
Definition at line 77 of file connection_monitor.h.
ros::Time actionlib::ConnectionMonitor::latest_status_time_ [private] |
Definition at line 72 of file connection_monitor.h.
ros::Subscriber& actionlib::ConnectionMonitor::result_sub_ [private] |
Definition at line 84 of file connection_monitor.h.
std::string actionlib::ConnectionMonitor::status_caller_id_ [private] |
Definition at line 70 of file connection_monitor.h.
bool actionlib::ConnectionMonitor::status_received_ [private] |
Definition at line 71 of file connection_monitor.h.