46 #define CONNECTION_DEBUG(fmt, ...) \ 47 ROS_DEBUG_NAMED("ConnectionMonitor", fmt, ## __VA_ARGS__) 49 #define CONNECTION_WARN(fmt, ...) \ 50 ROS_WARN_NAMED("ConnectionMonitor", fmt, ## __VA_ARGS__) 55 : feedback_sub_(feedback_sub), result_sub_(result_sub)
64 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
73 "goalConnectCallback: Trying to add [%s] to goalSubscribers, but it is already in the goalSubscribers list",
84 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
86 std::map<std::string, size_t>::iterator it;
91 "goalDisconnectCallback: Trying to remove [%s] to goalSubscribers, but it is not in the goalSubscribers list",
94 CONNECTION_DEBUG(
"goalDisconnectCallback: Removing [%s] from goalSubscribers",
98 goalSubscribers_.erase(it);
106 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
107 std::ostringstream ss;
112 ss <<
"\n - " << it->first;
121 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
130 "cancelConnectCallback: Trying to add [%s] to cancelSubscribers, but it is already in the cancelSubscribers list",
142 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
144 std::map<std::string, size_t>::iterator it;
149 "cancelDisconnectCallback: Trying to remove [%s] to cancelSubscribers, but it is not in the cancelSubscribers list",
152 CONNECTION_DEBUG(
"cancelDisconnectCallback: Removing [%s] from cancelSubscribers",
156 cancelSubscribers_.erase(it);
164 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
166 std::ostringstream ss;
171 ss <<
"\n - " << it->first;
178 const actionlib_msgs::GoalStatusArrayConstPtr & status,
const std::string & cur_status_caller_id)
180 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
185 "processStatus: Previously received status from [%s], but we now received status from [%s]. Did the ActionServer change?",
192 "processStatus: Just got our first status message from the ActionServer at node [%s]",
193 cur_status_caller_id.c_str());
205 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
208 CONNECTION_DEBUG(
"isServerConnected: Didn't receive status yet, so not connected yet");
214 "isServerConnected: Server [%s] has not yet subscribed to the goal topic, so not connected yet",
222 "isServerConnected: Server [%s] has not yet subscribed to the cancel topic, so not connected yet",
230 "isServerConnected: Client has not yet connected to feedback topic of server [%s]",
237 "isServerConnected: Client has not yet connected to result topic of server [%s]",
250 ROS_ERROR_NAMED(
"actionlib",
"Timeouts can't be negative. Timeout is [%.2fs]", timeout.
toSec());
255 boost::recursive_mutex::scoped_lock lock(
data_mutex_);
275 time_left = loop_period;
279 boost::posix_time::milliseconds(static_cast<int64_t>(time_left.
toSec() * 1000.0f)));
void goalConnectCallback(const ros::SingleSubscriberPublisher &pub)
void goalDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
#define CONNECTION_DEBUG(fmt,...)
void cancelConnectCallback(const ros::SingleSubscriberPublisher &pub)
std::map< std::string, size_t > goalSubscribers_
Duration & fromSec(double t)
boost::recursive_mutex data_mutex_
void cancelDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
#define CONNECTION_WARN(fmt,...)
std::string getSubscriberName() const
std::string cancelSubscribersString()
uint32_t getNumPublishers() const
std::string goalSubscribersString()
std::map< std::string, size_t > cancelSubscribers_
ros::Subscriber & result_sub_
ros::Time latest_status_time_
ConnectionMonitor(ros::Subscriber &feedback_sub, ros::Subscriber &result_sub)
bool waitForActionServerToStart(const ros::Duration &timeout=ros::Duration(0, 0), const ros::NodeHandle &nh=ros::NodeHandle())
void processStatus(const actionlib_msgs::GoalStatusArrayConstPtr &status, const std::string &cur_status_caller_id)
#define ROS_ERROR_NAMED(name,...)
boost::condition check_connection_condition_
ros::Subscriber & feedback_sub_
std::string status_caller_id_