00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
00029 #define ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
00030
00031 #include <typeinfo>
00032
00033 #include "ros/forwards.h"
00034 #include "ros/parameter_adapter.h"
00035 #include "ros/message_traits.h"
00036 #include "ros/builtin_message_traits.h"
00037 #include "ros/serialization.h"
00038 #include "ros/message.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 namespace serialization
00053 {
00054
00055
00056 template<typename M>
00057 struct PreDeserializeParams
00058 {
00059 boost::shared_ptr<M> message;
00060 boost::shared_ptr<std::map<std::string, std::string> > connection_header;
00061 };
00062
00066 template<typename M>
00067 struct PreDeserialize
00068 {
00069 static void notify(const PreDeserializeParams<M>& params)
00070 {
00071 }
00072 };
00073
00074 }
00075
00076 template<typename T>
00077 typename boost::enable_if<boost::is_base_of<ros::Message, T> >::type assignSubscriptionConnectionHeader(T* t, const boost::shared_ptr<M_string>& connection_header)
00078 {
00079 t->__connection_header = connection_header;
00080 }
00081
00082 template<typename T>
00083 typename boost::disable_if<boost::is_base_of<ros::Message, T> >::type assignSubscriptionConnectionHeader(T* t, const boost::shared_ptr<M_string>& connection_header)
00084 {
00085 }
00086
00087 struct SubscriptionCallbackHelperDeserializeParams
00088 {
00089 uint8_t* buffer;
00090 uint32_t length;
00091 boost::shared_ptr<M_string> connection_header;
00092 };
00093
00094 struct SubscriptionCallbackHelperCallParams
00095 {
00096 MessageEvent<void const> event;
00097 };
00098
00104 class SubscriptionCallbackHelper
00105 {
00106 public:
00107 virtual ~SubscriptionCallbackHelper() {}
00108 virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams&) = 0;
00109 virtual void call(SubscriptionCallbackHelperCallParams& params) = 0;
00110 virtual const std::type_info& getTypeInfo() = 0;
00111 virtual bool isConst() = 0;
00112 };
00113 typedef boost::shared_ptr<SubscriptionCallbackHelper> SubscriptionCallbackHelperPtr;
00114
00119 template<typename P, typename Enabled = void>
00120 class SubscriptionCallbackHelperT : public SubscriptionCallbackHelper
00121 {
00122 public:
00123 typedef ParameterAdapter<P> Adapter;
00124 typedef typename ParameterAdapter<P>::Message NonConstType;
00125 typedef typename ParameterAdapter<P>::Event Event;
00126 typedef typename boost::add_const<NonConstType>::type ConstType;
00127 typedef boost::shared_ptr<NonConstType> NonConstTypePtr;
00128 typedef boost::shared_ptr<ConstType> ConstTypePtr;
00129
00130 static const bool is_const = ParameterAdapter<P>::is_const;
00131
00132 typedef boost::function<void(typename Adapter::Parameter)> Callback;
00133 typedef boost::function<NonConstTypePtr()> CreateFunction;
00134
00135 SubscriptionCallbackHelperT(const Callback& callback, const CreateFunction& create = DefaultMessageCreator<NonConstType>())
00136 : callback_(callback)
00137 , create_(create)
00138 {}
00139
00140 void setCreateFunction(const CreateFunction& create)
00141 {
00142 create_ = create;
00143 }
00144
00145 virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams& params)
00146 {
00147 namespace ser = serialization;
00148
00149 NonConstTypePtr msg = create_();
00150
00151 if (!msg)
00152 {
00153 ROS_DEBUG("Allocation failed for message of type [%s]", getTypeInfo().name());
00154 return VoidConstPtr();
00155 }
00156
00157 assignSubscriptionConnectionHeader(msg.get(), params.connection_header);
00158
00159 ser::PreDeserializeParams<NonConstType> predes_params;
00160 predes_params.message = msg;
00161 predes_params.connection_header = params.connection_header;
00162 ser::PreDeserialize<NonConstType>::notify(predes_params);
00163
00164 ser::IStream stream(params.buffer, params.length);
00165 ser::deserialize(stream, *msg);
00166
00167 return VoidConstPtr(msg);
00168 }
00169
00170 virtual void call(SubscriptionCallbackHelperCallParams& params)
00171 {
00172 Event event(params.event, create_);
00173 callback_(ParameterAdapter<P>::getParameter(event));
00174 }
00175
00176 virtual const std::type_info& getTypeInfo()
00177 {
00178 return typeid(NonConstType);
00179 }
00180
00181 virtual bool isConst()
00182 {
00183 return ParameterAdapter<P>::is_const;
00184 }
00185
00186 private:
00187 Callback callback_;
00188 CreateFunction create_;
00189 };
00190
00191 }
00192
00193 #endif // ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H