subscription_callback_helper.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
29 #define ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
30 
31 #include <typeinfo>
32 
33 #include "common.h"
34 #include "ros/forwards.h"
35 #include "ros/parameter_adapter.h"
36 #include "ros/message_traits.h"
38 #include "ros/serialization.h"
39 #include "ros/message_event.h"
40 #include <ros/static_assert.h>
41 
42 #include <boost/type_traits/add_const.hpp>
43 #include <boost/type_traits/remove_const.hpp>
44 #include <boost/type_traits/remove_reference.hpp>
45 #include <boost/type_traits/is_base_of.hpp>
46 #include <boost/utility/enable_if.hpp>
47 #include <boost/make_shared.hpp>
48 
49 namespace ros
50 {
51 
53 {
54  uint8_t* buffer;
55  uint32_t length;
57 };
58 
60 {
62 };
63 
69 class ROSCPP_DECL SubscriptionCallbackHelper
70 {
71 public:
74  virtual void call(SubscriptionCallbackHelperCallParams& params) = 0;
75  virtual const std::type_info& getTypeInfo() = 0;
76  virtual bool isConst() = 0;
77  virtual bool hasHeader() = 0;
78 };
80 
86 template<typename P, typename Enabled = void>
88 {
89 public:
93  typedef typename boost::add_const<NonConstType>::type ConstType;
96 
98 
99  typedef boost::function<void(typename Adapter::Parameter)> Callback;
100  typedef boost::function<NonConstTypePtr()> CreateFunction;
101 
104  : callback_(callback)
105  , create_(create)
106  { }
107 
108  void setCreateFunction(const CreateFunction& create)
109  {
110  create_ = create;
111  }
112 
113  virtual bool hasHeader()
114  {
115  return message_traits::hasHeader<typename ParameterAdapter<P>::Message>();
116  }
117 
119  {
120  namespace ser = serialization;
121 
122  NonConstTypePtr msg = create_();
123 
124  if (!msg)
125  {
126  ROS_DEBUG("Allocation failed for message of type [%s]", getTypeInfo().name());
127  return VoidConstPtr();
128  }
129 
130  ser::PreDeserializeParams<NonConstType> predes_params;
131  predes_params.message = msg;
132  predes_params.connection_header = params.connection_header;
133  ser::PreDeserialize<NonConstType>::notify(predes_params);
134 
135  ser::IStream stream(params.buffer, params.length);
136  ser::deserialize(stream, *msg);
137 
138  return VoidConstPtr(msg);
139  }
140 
142  {
143  Event event(params.event, create_);
145  }
146 
147  virtual const std::type_info& getTypeInfo()
148  {
149  return typeid(NonConstType);
150  }
151 
152  virtual bool isConst()
153  {
155  }
156 
157 private:
160 };
161 
162 }
163 
164 #endif // ROSCPP_SUBSCRIPTION_CALLBACK_HELPER_H
ros::SubscriptionCallbackHelper::~SubscriptionCallbackHelper
virtual ~SubscriptionCallbackHelper()
Definition: subscription_callback_helper.h:72
parameter_adapter.h
ros::SubscriptionCallbackHelperT::SubscriptionCallbackHelperT
SubscriptionCallbackHelperT(const Callback &callback, const CreateFunction &create=DefaultMessageCreator< NonConstType >())
Definition: subscription_callback_helper.h:102
ros::SubscriptionCallbackHelperPtr
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
Definition: message_deserializer.h:42
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
Invoke an RPC service.
Definition: service.h:65
deserialize
void deserialize(Stream &stream, boost::array< T, N > &t)
ros::SubscriptionCallbackHelperT::Event
ParameterAdapter< P >::Event Event
Definition: subscription_callback_helper.h:92
ros::SubscriptionCallbackHelperT::call
virtual void call(SubscriptionCallbackHelperCallParams &params)
Definition: subscription_callback_helper.h:141
boost::shared_ptr< M_string >
forwards.h
ros::SubscriptionCallbackHelperDeserializeParams::buffer
uint8_t * buffer
Definition: subscription_callback_helper.h:54
ros
ros::SubscriptionCallbackHelperT::setCreateFunction
void setCreateFunction(const CreateFunction &create)
Definition: subscription_callback_helper.h:108
ros::SubscriptionCallbackHelperT::Adapter
ParameterAdapter< P > Adapter
Definition: subscription_callback_helper.h:90
ros::SubscriptionCallbackHelperT::callback_
Callback callback_
Definition: subscription_callback_helper.h:158
builtin_message_traits.h
ros::SubscriptionCallbackHelperT
Concrete generic implementation of SubscriptionCallbackHelper for any normal message type....
Definition: subscription_callback_helper.h:87
ros::ParameterAdapter
Generally not for outside use. Adapts a function parameter type into the message type,...
Definition: parameter_adapter.h:69
ros::SubscriptionCallbackHelperDeserializeParams::length
uint32_t length
Definition: subscription_callback_helper.h:55
ros::SubscriptionCallbackHelperCallParams::event
MessageEvent< void const > event
Definition: subscription_callback_helper.h:61
ros::SubscriptionCallbackHelperT::ConstType
boost::add_const< NonConstType >::type ConstType
Definition: subscription_callback_helper.h:93
ros::ParameterAdapter::Parameter
M Parameter
Definition: parameter_adapter.h:73
ros::SubscriptionCallbackHelperT::hasHeader
virtual bool hasHeader()
Definition: subscription_callback_helper.h:113
ros::SubscriptionCallbackHelperT::deserialize
virtual VoidConstPtr deserialize(const SubscriptionCallbackHelperDeserializeParams &params)
Definition: subscription_callback_helper.h:118
ros::DefaultMessageCreator
message_traits.h
ROS_DEBUG
#define ROS_DEBUG(...)
ros::SubscriptionCallbackHelperT::NonConstType
ParameterAdapter< P >::Message NonConstType
Definition: subscription_callback_helper.h:91
ros::VoidConstPtr
boost::shared_ptr< void const > VoidConstPtr
Definition: forwards.h:52
ros::SubscriptionCallbackHelperT::ConstTypePtr
boost::shared_ptr< ConstType > ConstTypePtr
Definition: subscription_callback_helper.h:95
ros::ParameterAdapter::Message
boost::remove_reference< typename boost::remove_const< M >::type >::type Message
Definition: parameter_adapter.h:71
serialization.h
ros::SubscriptionCallbackHelperT::is_const
static const bool is_const
Definition: subscription_callback_helper.h:97
ros::SubscriptionCallbackHelperT::CreateFunction
boost::function< NonConstTypePtr()> CreateFunction
Definition: subscription_callback_helper.h:100
ros::SubscriptionCallbackHelperDeserializeParams
Definition: subscription_callback_helper.h:52
ros::SubscriptionCallbackHelperT::Callback
boost::function< void(typename Adapter::Parameter)> Callback
Definition: subscription_callback_helper.h:99
ros::SubscriptionCallbackHelperT::create_
CreateFunction create_
Definition: subscription_callback_helper.h:159
ros::SubscriptionCallbackHelperT::isConst
virtual bool isConst()
Definition: subscription_callback_helper.h:152
hasHeader
bool hasHeader()
ros::SubscriptionCallbackHelper
Abstract base class used by subscriptions to deal with concrete message types through a common interf...
Definition: subscription_callback_helper.h:69
static_assert.h
ros::SubscriptionCallbackHelperDeserializeParams::connection_header
boost::shared_ptr< M_string > connection_header
Definition: subscription_callback_helper.h:56
message_event.h
ros::SubscriptionCallbackHelperT::getTypeInfo
virtual const std::type_info & getTypeInfo()
Definition: subscription_callback_helper.h:147
ros::SubscriptionCallbackHelperT::NonConstTypePtr
boost::shared_ptr< NonConstType > NonConstTypePtr
Definition: subscription_callback_helper.h:94
ros::SubscriptionCallbackHelperCallParams
Definition: subscription_callback_helper.h:59
ros::MessageEvent


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44