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


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12