service_callback_helper.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 Stanford University or 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_SERVICE_MESSAGE_HELPER_H
00029 #define ROSCPP_SERVICE_MESSAGE_HELPER_H
00030 
00031 #include "ros/forwards.h"
00032 #include "ros/common.h"
00033 #include "ros/message.h"
00034 #include "ros/message_traits.h"
00035 #include "ros/service_traits.h"
00036 #include "ros/serialization.h"
00037 
00038 #include <boost/type_traits/is_base_of.hpp>
00039 #include <boost/utility/enable_if.hpp>
00040 
00041 namespace ros
00042 {
00043 struct ROSCPP_DECL ServiceCallbackHelperCallParams
00044 {
00045   SerializedMessage request;
00046   SerializedMessage response;
00047   boost::shared_ptr<M_string> connection_header;
00048 };
00049 
00050 template<typename M>
00051 inline boost::shared_ptr<M> defaultServiceCreateFunction()
00052 {
00053   return boost::make_shared<M>();
00054 }
00055 
00056 template<typename MReq, typename MRes>
00057 struct ServiceSpecCallParams
00058 {
00059   boost::shared_ptr<MReq> request;
00060   boost::shared_ptr<MRes> response;
00061   boost::shared_ptr<M_string> connection_header;
00062 };
00063 
00069 template<typename MReq, typename MRes>
00070 class ServiceEvent
00071 {
00072 public:
00073   typedef MReq RequestType;
00074   typedef MRes ResponseType;
00075   typedef boost::shared_ptr<RequestType> RequestPtr;
00076   typedef boost::shared_ptr<ResponseType> ResponsePtr;
00077   typedef boost::function<bool(ServiceEvent<RequestType, ResponseType>&)> CallbackType;
00078 
00079   static bool call(const CallbackType& cb, ServiceSpecCallParams<RequestType, ResponseType>& params)
00080   {
00081     ServiceEvent<RequestType, ResponseType> event(params.request, params.response, params.connection_header);
00082     return cb(event);
00083   }
00084 
00085   ServiceEvent(const boost::shared_ptr<MReq const>& req, const boost::shared_ptr<MRes>& res, const boost::shared_ptr<M_string>& connection_header)
00086   : request_(req)
00087   , response_(res)
00088   , connection_header_(connection_header)
00089   {}
00090 
00094   const RequestType& getRequest() const { return *request_; }
00098   ResponseType& getResponse() const { return *response_; }
00102   M_string& getConnectionHeader() const { return *connection_header_; }
00103 
00107   const std::string& getCallerName() const { return (*connection_header_)["callerid"]; }
00108 private:
00109   boost::shared_ptr<RequestType const> request_;
00110   boost::shared_ptr<ResponseType> response_;
00111   boost::shared_ptr<M_string> connection_header_;
00112 };
00113 
00114 template<typename MReq, typename MRes>
00115 struct ServiceSpec
00116 {
00117   typedef MReq RequestType;
00118   typedef MRes ResponseType;
00119   typedef boost::shared_ptr<RequestType> RequestPtr;
00120   typedef boost::shared_ptr<ResponseType> ResponsePtr;
00121   typedef boost::function<bool(RequestType&, ResponseType&)> CallbackType;
00122 
00123   static bool call(const CallbackType& cb, ServiceSpecCallParams<RequestType, ResponseType>& params)
00124   {
00125     return cb(*params.request, *params.response);
00126   }
00127 };
00128 
00134 class ROSCPP_DECL ServiceCallbackHelper
00135 {
00136 public:
00137   virtual ~ServiceCallbackHelper() {}
00138   virtual bool call(ServiceCallbackHelperCallParams& params) = 0;
00139 };
00140 typedef boost::shared_ptr<ServiceCallbackHelper> ServiceCallbackHelperPtr;
00141 
00145 template<typename Spec>
00146 class ServiceCallbackHelperT : public ServiceCallbackHelper
00147 {
00148 public:
00149   typedef typename Spec::RequestType RequestType;
00150   typedef typename Spec::ResponseType ResponseType;
00151   typedef typename Spec::RequestPtr RequestPtr;
00152   typedef typename Spec::ResponsePtr ResponsePtr;
00153   typedef typename Spec::CallbackType Callback;
00154   typedef boost::function<RequestPtr()> ReqCreateFunction;
00155   typedef boost::function<ResponsePtr()> ResCreateFunction;
00156 
00157   ServiceCallbackHelperT(const Callback& callback, 
00158                          const ReqCreateFunction& create_req = 
00159                          // these static casts are legally unnecessary, but
00160                          // here to keep clang 2.8 from getting confused
00161                          static_cast<RequestPtr(*)()>(defaultServiceCreateFunction<RequestType>), 
00162                          const ResCreateFunction& create_res = 
00163                          static_cast<ResponsePtr(*)()>(defaultServiceCreateFunction<ResponseType>))
00164   : callback_(callback)
00165   , create_req_(create_req)
00166   , create_res_(create_res)
00167   {
00168   }
00169 
00170   virtual bool call(ServiceCallbackHelperCallParams& params)
00171   {
00172     namespace ser = serialization;
00173     RequestPtr req(create_req_());
00174     ResponsePtr res(create_res_());
00175 
00176     ser::deserializeMessage(params.request, *req);
00177 
00178     ServiceSpecCallParams<RequestType, ResponseType> call_params;
00179     call_params.request = req;
00180     call_params.response = res;
00181     call_params.connection_header = params.connection_header;
00182     bool ok = Spec::call(callback_, call_params);
00183     params.response = ser::serializeServiceResponse(ok, *res);
00184     return ok;
00185   }
00186 
00187 private:
00188   Callback callback_;
00189   ReqCreateFunction create_req_;
00190   ResCreateFunction create_res_;
00191 };
00192 
00193 }
00194 
00195 #endif // ROSCPP_SERVICE_MESSAGE_HELPER_H


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Thu Jun 6 2019 21:10:05