connection_monitor.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
36 #define ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
37 
38 #include <ros/ros.h>
39 #include <actionlib_msgs/GoalStatusArray.h>
40 
41 #include <actionlib/decl.h>
42 
43 #include <boost/thread/condition.hpp>
44 #include <boost/thread/recursive_mutex.hpp>
45 
46 #include <set>
47 #include <string>
48 #include <map>
49 
50 namespace actionlib
51 {
52 
54 {
55 public:
56  ConnectionMonitor(ros::Subscriber & feedback_sub, ros::Subscriber & result_sub);
57 
58  void goalConnectCallback(const ros::SingleSubscriberPublisher & pub);
59 
60  void goalDisconnectCallback(const ros::SingleSubscriberPublisher & pub);
61 
62  void cancelConnectCallback(const ros::SingleSubscriberPublisher & pub);
63 
64  void cancelDisconnectCallback(const ros::SingleSubscriberPublisher & pub);
65 
66  void processStatus(const actionlib_msgs::GoalStatusArrayConstPtr & status,
67  const std::string & cur_status_caller_id);
68 
69  bool waitForActionServerToStart(const ros::Duration & timeout = ros::Duration(0, 0),
70  const ros::NodeHandle & nh = ros::NodeHandle() );
71  bool isServerConnected();
72 
73 private:
74  // status stuff
75  std::string status_caller_id_;
78 
79  boost::condition check_connection_condition_;
80 
81  boost::recursive_mutex data_mutex_;
82  std::map<std::string, size_t> goalSubscribers_;
83  std::map<std::string, size_t> cancelSubscribers_;
84 
85  std::string goalSubscribersString();
86  std::string cancelSubscribersString();
87 
90 };
91 
92 } // namespace actionlib
93 
94 #endif // ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
#define ACTIONLIB_DECL
Definition: decl.h:52
std::map< std::string, size_t > goalSubscribers_
boost::recursive_mutex data_mutex_
std::map< std::string, size_t > cancelSubscribers_
boost::condition check_connection_condition_


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Aug 24 2020 03:40:47