xmlrpc_manager.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #ifndef ROSCPP_XMLRPC_MANAGER_H
00029 #define ROSCPP_XMLRPC_MANAGER_H
00030 
00031 #include <string>
00032 #include <set>
00033 #include <boost/function.hpp>
00034 #include <boost/thread/mutex.hpp>
00035 #include <boost/thread/thread.hpp>
00036 #include <boost/enable_shared_from_this.hpp>
00037 
00038 #include "common.h"
00039 #include "XmlRpc.h"
00040 
00041 #include <ros/time.h>
00042 
00043 
00044 namespace ros
00045 {
00046 
00050 namespace xmlrpc
00051 {
00052 XmlRpc::XmlRpcValue responseStr(int code, const std::string& msg, const std::string& response);
00053 XmlRpc::XmlRpcValue responseInt(int code, const std::string& msg, int response);
00054 XmlRpc::XmlRpcValue responseBool(int code, const std::string& msg, bool response);
00055 }
00056 
00057 class XMLRPCCallWrapper;
00058 typedef boost::shared_ptr<XMLRPCCallWrapper> XMLRPCCallWrapperPtr;
00059 
00060 class ROSCPP_DECL ASyncXMLRPCConnection : public boost::enable_shared_from_this<ASyncXMLRPCConnection>
00061 {
00062 public:
00063   virtual ~ASyncXMLRPCConnection() {}
00064 
00065   virtual void addToDispatch(XmlRpc::XmlRpcDispatch* disp) = 0;
00066   virtual void removeFromDispatch(XmlRpc::XmlRpcDispatch* disp) = 0;
00067 
00068   virtual bool check() = 0;
00069 };
00070 typedef boost::shared_ptr<ASyncXMLRPCConnection> ASyncXMLRPCConnectionPtr;
00071 typedef std::set<ASyncXMLRPCConnectionPtr> S_ASyncXMLRPCConnection;
00072 
00073 class ROSCPP_DECL CachedXmlRpcClient
00074 {
00075 public:
00076   CachedXmlRpcClient(XmlRpc::XmlRpcClient *c)
00077   : in_use_(false)
00078   , client_(c)
00079   {
00080   }
00081 
00082   bool in_use_;
00083   ros::WallTime last_use_time_; // for reaping
00084   XmlRpc::XmlRpcClient* client_;
00085 
00086   static const ros::WallDuration s_zombie_time_; // how long before it is toasted
00087 };
00088 
00089 class XMLRPCManager;
00090 typedef boost::shared_ptr<XMLRPCManager> XMLRPCManagerPtr;
00091 
00092 typedef boost::function<void(XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&)> XMLRPCFunc;
00093 
00094 class ROSCPP_DECL XMLRPCManager
00095 {
00096 public:
00097   static const XMLRPCManagerPtr& instance();
00098 
00099   XMLRPCManager();
00100   ~XMLRPCManager();
00101 
00112   bool validateXmlrpcResponse(const std::string& method, 
00113                               XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload);
00114 
00118   inline const std::string& getServerURI() const { return uri_; }
00119   inline uint32_t getServerPort() const { return port_; }
00120 
00121   XmlRpc::XmlRpcClient* getXMLRPCClient(const std::string& host, const int port, const std::string& uri);
00122   void releaseXMLRPCClient(XmlRpc::XmlRpcClient* c);
00123 
00124   void addASyncConnection(const ASyncXMLRPCConnectionPtr& conn);
00125   void removeASyncConnection(const ASyncXMLRPCConnectionPtr& conn);
00126 
00127   bool bind(const std::string& function_name, const XMLRPCFunc& cb);
00128   void unbind(const std::string& function_name);
00129 
00130   void start();
00131   void shutdown();
00132 
00133   bool isShuttingDown() { return shutting_down_; }
00134 
00135 private:
00136   void serverThreadFunc();
00137 
00138   std::string uri_;
00139   int port_;
00140   boost::thread server_thread_;
00141 
00142 #if defined(__APPLE__)
00143   // OSX has problems with lots of concurrent xmlrpc calls
00144   boost::mutex xmlrpc_call_mutex_;
00145 #endif
00146   XmlRpc::XmlRpcServer server_;
00147   typedef std::vector<CachedXmlRpcClient> V_CachedXmlRpcClient;
00148   V_CachedXmlRpcClient clients_;
00149   boost::mutex clients_mutex_;
00150 
00151   bool shutting_down_;
00152 
00153   ros::WallDuration master_retry_timeout_;
00154 
00155   S_ASyncXMLRPCConnection added_connections_;
00156   boost::mutex added_connections_mutex_;
00157   S_ASyncXMLRPCConnection removed_connections_;
00158   boost::mutex removed_connections_mutex_;
00159 
00160   S_ASyncXMLRPCConnection connections_;
00161 
00162 
00163   struct FunctionInfo
00164   {
00165     std::string name;
00166     XMLRPCFunc function;
00167     XMLRPCCallWrapperPtr wrapper;
00168   };
00169   typedef std::map<std::string, FunctionInfo> M_StringToFuncInfo;
00170   boost::mutex functions_mutex_;
00171   M_StringToFuncInfo functions_;
00172 
00173   volatile bool unbind_requested_;
00174 };
00175 
00176 }
00177 
00178 #endif


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44