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 T>
00051 void
00052 assignServiceConnectionHeader(T* t, const boost::shared_ptr<M_string>& connection_header,
00053                               typename boost::enable_if<ros::message_traits::IsMessage<T> >::type*_ = 0)
00054 {
00055   (void)_; // warning stopper
00056   t->__connection_header = connection_header;
00057 }
00058 
00059 template<typename T>
00060 void
00061 assignServiceConnectionHeader(T*, const boost::shared_ptr<M_string>&,
00062                               typename boost::disable_if<ros::message_traits::IsMessage<T> >::type*_ = 0)
00063 { 
00064   (void)_;
00065 }
00066 
00067 template<typename M>
00068 inline boost::shared_ptr<M> defaultServiceCreateFunction()
00069 {
00070   return boost::shared_ptr<M>(new M);
00071 }
00072 
00073 template<typename MReq, typename MRes>
00074 struct ServiceSpecCallParams
00075 {
00076   boost::shared_ptr<MReq> request;
00077   boost::shared_ptr<MRes> response;
00078   boost::shared_ptr<M_string> connection_header;
00079 };
00080 
00086 template<typename MReq, typename MRes>
00087 class ServiceEvent
00088 {
00089 public:
00090   typedef MReq RequestType;
00091   typedef MRes ResponseType;
00092   typedef boost::shared_ptr<RequestType> RequestPtr;
00093   typedef boost::shared_ptr<ResponseType> ResponsePtr;
00094   typedef boost::function<bool(ServiceEvent<RequestType, ResponseType>&)> CallbackType;
00095 
00096   static bool call(const CallbackType& cb, ServiceSpecCallParams<RequestType, ResponseType>& params)
00097   {
00098     ServiceEvent<RequestType, ResponseType> event(params.request, params.response, params.connection_header);
00099     return cb(event);
00100   }
00101 
00102   ServiceEvent(const boost::shared_ptr<MReq const>& req, const boost::shared_ptr<MRes>& res, const boost::shared_ptr<M_string>& connection_header)
00103   : request_(req)
00104   , response_(res)
00105   , connection_header_(connection_header)
00106   {}
00107 
00111   const RequestType& getRequest() const { return *request_; }
00115   ResponseType& getResponse() const { return *response_; }
00119   M_string& getConnectionHeader() const { return *connection_header_; }
00120 
00124   const std::string& getCallerName() const { return (*connection_header_)["callerid"]; }
00125 private:
00126   boost::shared_ptr<RequestType const> request_;
00127   boost::shared_ptr<ResponseType> response_;
00128   boost::shared_ptr<M_string> connection_header_;
00129 };
00130 
00131 template<typename MReq, typename MRes>
00132 struct ServiceSpec
00133 {
00134   typedef MReq RequestType;
00135   typedef MRes ResponseType;
00136   typedef boost::shared_ptr<RequestType> RequestPtr;
00137   typedef boost::shared_ptr<ResponseType> ResponsePtr;
00138   typedef boost::function<bool(RequestType&, ResponseType&)> CallbackType;
00139 
00140   static bool call(const CallbackType& cb, ServiceSpecCallParams<RequestType, ResponseType>& params)
00141   {
00142     return cb(*params.request, *params.response);
00143   }
00144 };
00145 
00151 class ROSCPP_DECL ServiceCallbackHelper
00152 {
00153 public:
00154   virtual ~ServiceCallbackHelper() {}
00155   virtual bool call(ServiceCallbackHelperCallParams& params) = 0;
00156 };
00157 typedef boost::shared_ptr<ServiceCallbackHelper> ServiceCallbackHelperPtr;
00158 
00162 template<typename Spec>
00163 class ServiceCallbackHelperT : public ServiceCallbackHelper
00164 {
00165 public:
00166   typedef typename Spec::RequestType RequestType;
00167   typedef typename Spec::ResponseType ResponseType;
00168   typedef typename Spec::RequestPtr RequestPtr;
00169   typedef typename Spec::ResponsePtr ResponsePtr;
00170   typedef typename Spec::CallbackType Callback;
00171   typedef boost::function<RequestPtr()> ReqCreateFunction;
00172   typedef boost::function<ResponsePtr()> ResCreateFunction;
00173 
00174   ServiceCallbackHelperT(const Callback& callback, 
00175                          const ReqCreateFunction& create_req = 
00176                          // these static casts are legally unnecessary, but
00177                          // here to keep clang 2.8 from getting confused
00178                          static_cast<RequestPtr(*)()>(defaultServiceCreateFunction<RequestType>), 
00179                          const ResCreateFunction& create_res = 
00180                          static_cast<ResponsePtr(*)()>(defaultServiceCreateFunction<ResponseType>))
00181   : callback_(callback)
00182   , create_req_(create_req)
00183   , create_res_(create_res)
00184   {
00185   }
00186 
00187   virtual bool call(ServiceCallbackHelperCallParams& params)
00188   {
00189     namespace ser = serialization;
00190     RequestPtr req(create_req_());
00191     ResponsePtr res(create_res_());
00192 
00193     assignServiceConnectionHeader(req.get(), params.connection_header);
00194     ser::deserializeMessage(params.request, *req);
00195 
00196     ServiceSpecCallParams<RequestType, ResponseType> call_params;
00197     call_params.request = req;
00198     call_params.response = res;
00199     call_params.connection_header = params.connection_header;
00200     bool ok = Spec::call(callback_, call_params);
00201     params.response = ser::serializeServiceResponse(ok, *res);
00202     return ok;
00203   }
00204 
00205 private:
00206   Callback callback_;
00207   ReqCreateFunction create_req_;
00208   ResCreateFunction create_res_;
00209 };
00210 
00211 }
00212 
00213 #endif // ROSCPP_SERVICE_MESSAGE_HELPER_H


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:52