Public Member Functions | Private Member Functions | Private Attributes | List of all members
actionlib::ConnectionMonitor Class Reference

#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, const std::string &cur_status_caller_id)
 
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::map< std::string, size_t > cancelSubscribers_
 
boost::condition check_connection_condition_
 
boost::recursive_mutex data_mutex_
 
ros::Subscriberfeedback_sub_
 
std::map< std::string, size_t > goalSubscribers_
 
ros::Time latest_status_time_
 
ros::Subscriberresult_sub_
 
std::string status_caller_id_
 
bool status_received_
 

Detailed Description

Definition at line 85 of file connection_monitor.h.

Constructor & Destructor Documentation

◆ ConnectionMonitor()

actionlib::ConnectionMonitor::ConnectionMonitor ( ros::Subscriber feedback_sub,
ros::Subscriber result_sub 
)

Definition at line 53 of file connection_monitor.cpp.

Member Function Documentation

◆ cancelConnectCallback()

void actionlib::ConnectionMonitor::cancelConnectCallback ( const ros::SingleSubscriberPublisher pub)

Definition at line 119 of file connection_monitor.cpp.

◆ cancelDisconnectCallback()

void actionlib::ConnectionMonitor::cancelDisconnectCallback ( const ros::SingleSubscriberPublisher pub)

Definition at line 139 of file connection_monitor.cpp.

◆ cancelSubscribersString()

std::string actionlib::ConnectionMonitor::cancelSubscribersString ( )
private

Definition at line 162 of file connection_monitor.cpp.

◆ goalConnectCallback()

void actionlib::ConnectionMonitor::goalConnectCallback ( const ros::SingleSubscriberPublisher pub)

Definition at line 62 of file connection_monitor.cpp.

◆ goalDisconnectCallback()

void actionlib::ConnectionMonitor::goalDisconnectCallback ( const ros::SingleSubscriberPublisher pub)

Definition at line 82 of file connection_monitor.cpp.

◆ goalSubscribersString()

std::string actionlib::ConnectionMonitor::goalSubscribersString ( )
private

Definition at line 104 of file connection_monitor.cpp.

◆ isServerConnected()

bool actionlib::ConnectionMonitor::isServerConnected ( )

Definition at line 203 of file connection_monitor.cpp.

◆ processStatus()

void actionlib::ConnectionMonitor::processStatus ( const actionlib_msgs::GoalStatusArrayConstPtr &  status,
const std::string &  cur_status_caller_id 
)

Definition at line 177 of file connection_monitor.cpp.

◆ waitForActionServerToStart()

bool actionlib::ConnectionMonitor::waitForActionServerToStart ( const ros::Duration timeout = ros::Duration(0, 0),
const ros::NodeHandle nh = ros::NodeHandle() 
)

Definition at line 246 of file connection_monitor.cpp.

Member Data Documentation

◆ cancelSubscribers_

std::map<std::string, size_t> actionlib::ConnectionMonitor::cancelSubscribers_
private

Definition at line 147 of file connection_monitor.h.

◆ check_connection_condition_

boost::condition actionlib::ConnectionMonitor::check_connection_condition_
private

Definition at line 143 of file connection_monitor.h.

◆ data_mutex_

boost::recursive_mutex actionlib::ConnectionMonitor::data_mutex_
private

Definition at line 145 of file connection_monitor.h.

◆ feedback_sub_

ros::Subscriber& actionlib::ConnectionMonitor::feedback_sub_
private

Definition at line 152 of file connection_monitor.h.

◆ goalSubscribers_

std::map<std::string, size_t> actionlib::ConnectionMonitor::goalSubscribers_
private

Definition at line 146 of file connection_monitor.h.

◆ latest_status_time_

ros::Time actionlib::ConnectionMonitor::latest_status_time_
private

Definition at line 141 of file connection_monitor.h.

◆ result_sub_

ros::Subscriber& actionlib::ConnectionMonitor::result_sub_
private

Definition at line 153 of file connection_monitor.h.

◆ status_caller_id_

std::string actionlib::ConnectionMonitor::status_caller_id_
private

Definition at line 139 of file connection_monitor.h.

◆ status_received_

bool actionlib::ConnectionMonitor::status_received_
private

Definition at line 140 of file connection_monitor.h.


The documentation for this class was generated from the following files:


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55