subscription_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_SUBSCRIPTION_CALLBACK_HELPER_H
00029 #define ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
00030 
00031 #include <typeinfo>
00032 
00033 #include "common.h"
00034 #include "ros/forwards.h"
00035 #include "ros/parameter_adapter.h"
00036 #include "ros/message_traits.h"
00037 #include "ros/builtin_message_traits.h"
00038 #include "ros/serialization.h"
00039 #include "ros/message_event.h"
00040 #include <ros/static_assert.h>
00041 
00042 #include <boost/type_traits/add_const.hpp>
00043 #include <boost/type_traits/remove_const.hpp>
00044 #include <boost/type_traits/remove_reference.hpp>
00045 #include <boost/type_traits/is_base_of.hpp>
00046 #include <boost/utility/enable_if.hpp>
00047 #include <boost/make_shared.hpp>
00048 
00049 namespace ros
00050 {
00051 
00052 struct SubscriptionCallbackHelperDeserializeParams
00053 {
00054   uint8_t* buffer;
00055   uint32_t length;
00056   boost::shared_ptr<M_string> connection_header;
00057 };
00058 
00059 struct ROSCPP_DECL SubscriptionCallbackHelperCallParams
00060 {
00061   MessageEvent<void const> event;
00062 };
00063 
00069 class ROSCPP_DECL SubscriptionCallbackHelper
00070 {
00071 public:
00072   virtual ~SubscriptionCallbackHelper() {}
00073   virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams&) = 0;
00074   virtual void call(SubscriptionCallbackHelperCallParams& params) = 0;
00075   virtual const std::type_info& getTypeInfo() = 0;
00076   virtual bool isConst() = 0;
00077   virtual bool hasHeader() = 0;
00078 };
00079 typedef boost::shared_ptr<SubscriptionCallbackHelper> SubscriptionCallbackHelperPtr;
00080 
00086 template<typename P, typename Enabled = void>
00087 class SubscriptionCallbackHelperT : public SubscriptionCallbackHelper
00088 {
00089 public:
00090   typedef ParameterAdapter<P> Adapter;
00091   typedef typename ParameterAdapter<P>::Message NonConstType;
00092   typedef typename ParameterAdapter<P>::Event Event;
00093   typedef typename boost::add_const<NonConstType>::type ConstType;
00094   typedef boost::shared_ptr<NonConstType> NonConstTypePtr;
00095   typedef boost::shared_ptr<ConstType> ConstTypePtr;
00096 
00097   static const bool is_const = ParameterAdapter<P>::is_const;
00098 
00099   typedef boost::function<void(typename Adapter::Parameter)> Callback;
00100   typedef boost::function<NonConstTypePtr()> CreateFunction;
00101 
00102   SubscriptionCallbackHelperT(const Callback& callback, 
00103                               const CreateFunction& create = DefaultMessageCreator<NonConstType>())
00104     : callback_(callback)
00105     , create_(create)
00106   { }
00107 
00108   void setCreateFunction(const CreateFunction& create)
00109   {
00110     create_ = create;
00111   }
00112 
00113   virtual bool hasHeader()
00114   {
00115      return message_traits::hasHeader<typename ParameterAdapter<P>::Message>();
00116   }
00117 
00118   virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams& params)
00119   {
00120     namespace ser = serialization;
00121 
00122     NonConstTypePtr msg = create_();
00123 
00124     if (!msg)
00125     {
00126       ROS_DEBUG("Allocation failed for message of type [%s]", getTypeInfo().name());
00127       return VoidConstPtr();
00128     }
00129 
00130     ser::PreDeserializeParams<NonConstType> predes_params;
00131     predes_params.message = msg;
00132     predes_params.connection_header = params.connection_header;
00133     ser::PreDeserialize<NonConstType>::notify(predes_params);
00134 
00135     ser::IStream stream(params.buffer, params.length);
00136     ser::deserialize(stream, *msg);
00137 
00138     return VoidConstPtr(msg);
00139   }
00140 
00141   virtual void call(SubscriptionCallbackHelperCallParams& params)
00142   {
00143     Event event(params.event, create_);
00144     callback_(ParameterAdapter<P>::getParameter(event));
00145   }
00146 
00147   virtual const std::type_info& getTypeInfo()
00148   {
00149     return typeid(NonConstType);
00150   }
00151 
00152   virtual bool isConst()
00153   {
00154     return ParameterAdapter<P>::is_const;
00155   }
00156 
00157 private:
00158   Callback callback_;
00159   CreateFunction create_;
00160 };
00161 
00162 }
00163 
00164 #endif // ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47