xmlrpc_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_XMLRPC_MANAGER_H
29 #define ROSCPP_XMLRPC_MANAGER_H
30 
31 #include <string>
32 #include <set>
33 #include <boost/function.hpp>
34 #include <boost/thread/mutex.hpp>
35 #include <boost/thread/thread.hpp>
36 #include <boost/enable_shared_from_this.hpp>
37 
38 #include "common.h"
39 #include "xmlrpcpp/XmlRpc.h"
40 
41 #include <ros/time.h>
42 
43 
44 namespace ros
45 {
46 
50 namespace xmlrpc
51 {
52 XmlRpc::XmlRpcValue responseStr(int code, const std::string& msg, const std::string& response);
53 XmlRpc::XmlRpcValue responseInt(int code, const std::string& msg, int response);
54 XmlRpc::XmlRpcValue responseBool(int code, const std::string& msg, bool response);
55 }
56 
59 
60 class ROSCPP_DECL ASyncXMLRPCConnection : public boost::enable_shared_from_this<ASyncXMLRPCConnection>
61 {
62 public:
64 
65  virtual void addToDispatch(XmlRpc::XmlRpcDispatch* disp) = 0;
66  virtual void removeFromDispatch(XmlRpc::XmlRpcDispatch* disp) = 0;
67 
68  virtual bool check() = 0;
69 };
71 typedef std::set<ASyncXMLRPCConnectionPtr> S_ASyncXMLRPCConnection;
72 
73 class ROSCPP_DECL CachedXmlRpcClient
74 {
75 public:
77  : in_use_(false)
78  , client_(c)
79  {
80  }
81 
82  bool in_use_;
85 
86  static const ros::WallDuration s_zombie_time_; // how long before it is toasted
87 };
88 
89 class XMLRPCManager;
91 
92 typedef boost::function<void(XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&)> XMLRPCFunc;
93 
94 class ROSCPP_DECL XMLRPCManager
95 {
96 public:
97  static const XMLRPCManagerPtr& instance();
98 
99  XMLRPCManager();
100  ~XMLRPCManager();
101 
112  bool validateXmlrpcResponse(const std::string& method,
113  XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload);
114 
118  inline const std::string& getServerURI() const { return uri_; }
119  inline uint32_t getServerPort() const { return port_; }
120 
121  XmlRpc::XmlRpcClient* getXMLRPCClient(const std::string& host, const int port, const std::string& uri);
122  void releaseXMLRPCClient(XmlRpc::XmlRpcClient* c);
123 
124  void addASyncConnection(const ASyncXMLRPCConnectionPtr& conn);
125  void removeASyncConnection(const ASyncXMLRPCConnectionPtr& conn);
126 
127  bool bind(const std::string& function_name, const XMLRPCFunc& cb);
128  void unbind(const std::string& function_name);
129 
130  void start();
131  void shutdown();
132 
133  bool isShuttingDown() { return shutting_down_; }
134 
135 private:
136  void serverThreadFunc();
137 
138  std::string uri_;
139  int port_;
140  boost::thread server_thread_;
141 
142 #if defined(__APPLE__)
143  // OSX has problems with lots of concurrent xmlrpc calls
144  boost::mutex xmlrpc_call_mutex_;
145 #endif
147  typedef std::vector<CachedXmlRpcClient> V_CachedXmlRpcClient;
148  V_CachedXmlRpcClient clients_;
149  boost::mutex clients_mutex_;
150 
152 
154 
155  S_ASyncXMLRPCConnection added_connections_;
157  S_ASyncXMLRPCConnection removed_connections_;
159 
160  S_ASyncXMLRPCConnection connections_;
161 
162 
164  {
165  std::string name;
166  XMLRPCFunc function;
167  XMLRPCCallWrapperPtr wrapper;
168  };
169  typedef std::map<std::string, FunctionInfo> M_StringToFuncInfo;
170  boost::mutex functions_mutex_;
171  M_StringToFuncInfo functions_;
172 
173  volatile bool unbind_requested_;
174 };
175 
176 }
177 
178 #endif
ros::SteadyTime last_use_time_
XmlRpc::XmlRpcClient * client_
volatile bool unbind_requested_
ROSCPP_DECL bool check()
Check whether the master is up.
Definition: master.cpp:119
boost::mutex added_connections_mutex_
XmlRpc::XmlRpcValue responseBool(int code, const std::string &msg, bool response)
M_StringToFuncInfo functions_
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:293
boost::thread server_thread_
boost::shared_ptr< ASyncXMLRPCConnection > ASyncXMLRPCConnectionPtr
XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
V_CachedXmlRpcClient clients_
boost::shared_ptr< XMLRPCManager > XMLRPCManagerPtr
Definition: forwards.h:188
ros::WallDuration master_retry_timeout_
XmlRpc::XmlRpcValue responseStr(int code, const std::string &msg, const std::string &response)
boost::mutex functions_mutex_
S_ASyncXMLRPCConnection connections_
std::vector< CachedXmlRpcClient > V_CachedXmlRpcClient
boost::mutex removed_connections_mutex_
boost::function< void(XmlRpc::XmlRpcValue &, XmlRpc::XmlRpcValue &)> XMLRPCFunc
const std::string & getServerURI() const
Get the xmlrpc server URI of this node.
static const ros::WallDuration s_zombie_time_
CachedXmlRpcClient(XmlRpc::XmlRpcClient *c)
boost::mutex clients_mutex_
std::set< ASyncXMLRPCConnectionPtr > S_ASyncXMLRPCConnection
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:578
boost::shared_ptr< XMLRPCCallWrapper > XMLRPCCallWrapperPtr
S_ASyncXMLRPCConnection removed_connections_
S_ASyncXMLRPCConnection added_connections_
uint32_t getServerPort() const
XmlRpc::XmlRpcServer server_
std::map< std::string, FunctionInfo > M_StringToFuncInfo


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:26