message_event.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 /*
4  * Copyright (C) 2010, Willow Garage, Inc.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef ROSCPP_MESSAGE_EVENT_H
31 #define ROSCPP_MESSAGE_EVENT_H
32 
33 #include "ros/time.h"
34 #include <ros/datatypes.h>
35 #include <ros/message_traits.h>
36 
37 //#include <boost/type_traits/is_void.hpp>
38 //#include <boost/type_traits/is_base_of.hpp>
39 //#include <boost/type_traits/is_const.hpp>
40 //#include <boost/type_traits/add_const.hpp>
41 //#include <boost/type_traits/remove_const.hpp>
42 //#include <boost/utility/enable_if.hpp>
43 //#include <boost/function.hpp>
44 //#include <boost/make_shared.hpp>
45 
46 namespace roswrap
47 {
48 
49 template<typename M>
51 {
52  std::shared_ptr<M> operator()()
53  {
54  return std::make_shared<M>();
55  }
56 };
57 
58 template<typename M>
59 ROS_DEPRECATED inline std::shared_ptr<M> defaultMessageCreateFunction()
60 {
61  return DefaultMessageCreator<M>()();
62 }
63 
69 template<typename M>
71 {
72 public:
75  typedef std::shared_ptr<Message> MessagePtr;
76  typedef std::shared_ptr<ConstMessage> ConstMessagePtr;
77  typedef std::function<MessagePtr()> CreateFunction;
78 
80  : nonconst_need_copy_(true)
81  {}
82 
84  {
85  *this = rhs;
86  }
87 
89  {
90  *this = rhs;
91  }
92 
93  MessageEvent(const MessageEvent<Message>& rhs, bool nonconst_need_copy)
94  {
95  *this = rhs;
96  nonconst_need_copy_ = nonconst_need_copy;
97  }
98 
99  MessageEvent(const MessageEvent<ConstMessage>& rhs, bool nonconst_need_copy)
100  {
101  *this = rhs;
102  nonconst_need_copy_ = nonconst_need_copy;
103  }
104 
106  {
107  init(std::const_pointer_cast<Message>(std::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
108  }
109 
114  {
115  init(message, std::shared_ptr<M_string>(), ros::Time::now(), true, ros::DefaultMessageCreator<Message>());
116  }
117 
118  MessageEvent(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
119  {
120  init(message, connection_header, receipt_time, true, ros::DefaultMessageCreator<Message>());
121  }
122 
123  MessageEvent(const ConstMessagePtr& message, ros::Time receipt_time)
124  {
125  init(message, std::shared_ptr<M_string>(), receipt_time, true, ros::DefaultMessageCreator<Message>());
126  }
127 
128  MessageEvent(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
129  {
130  init(message, connection_header, receipt_time, nonconst_need_copy, create);
131  }
132 
133  void init(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
134  {
135  message_ = message;
136  connection_header_ = connection_header;
137  receipt_time_ = receipt_time;
138  nonconst_need_copy_ = nonconst_need_copy;
139  create_ = create;
140  }
141 
143  {
144  init(std::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
145  message_copy_.reset();
146  }
147 
149  {
150  init(std::const_pointer_cast<Message>(std::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
151  message_copy_.reset();
152  }
153 
159  std::shared_ptr<M> getMessage() const
160  {
161  return copyMessageIfNecessary<M>();
162  }
163 
167  const std::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
172  const std::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }
173 
177  const std::string& getPublisherName() const { return connection_header_ ? (*connection_header_)["callerid"] : s_unknown_publisher_string_; }
178 
183 
184  bool nonConstWillCopy() const { return nonconst_need_copy_; }
185  bool getMessageWillCopy() const { return !std::is_const<M>::value && nonconst_need_copy_; }
186 
187  bool operator<(const MessageEvent<M>& rhs)
188  {
189  if (message_ != rhs.message_)
190  {
191  return message_ < rhs.message_;
192  }
193 
194  if (receipt_time_ != rhs.receipt_time_)
195  {
196  return receipt_time_ < rhs.receipt_time_;
197  }
198 
200  }
201 
202  bool operator==(const MessageEvent<M>& rhs)
203  {
205  }
206 
207  bool operator!=(const MessageEvent<M>& rhs)
208  {
209  return !(*this == rhs);
210  }
211 
212  const CreateFunction& getMessageFactory() const { return create_; }
213 
214 private:
215  template<typename M2>
216  typename std::enable_if<!std::is_void<M2>::value, std::shared_ptr<M> >::type copyMessageIfNecessary() const
217  {
218  if (std::is_const<M>::value || !nonconst_need_copy_)
219  {
220  return std::const_pointer_cast<Message>(message_);
221  }
222 
223  if (message_copy_)
224  {
225  return message_copy_;
226  }
227 
228  assert(create_);
231 
232  return message_copy_;
233  }
234 
235  template<typename M2>
236  typename std::enable_if<std::is_void<M2>::value, std::shared_ptr<M> >::type copyMessageIfNecessary() const
237  {
238  return std::const_pointer_cast<Message>(message_);
239  }
240 
242  // Kind of ugly to make this mutable, but it means we can pass a const MessageEvent to a callback and not worry about other things being modified
244  std::shared_ptr<M_string> connection_header_;
248 
249  static const std::string s_unknown_publisher_string_;
250 };
251 
252 template<typename M> const std::string MessageEvent<M>::s_unknown_publisher_string_("unknown_publisher");
253 
254 
255 }
256 
257 #endif // ROSCPP_MESSAGE_EVENT_H
roswrap::MessageEvent::MessageEvent
MessageEvent(const MessageEvent< Message > &rhs)
Definition: message_event.h:83
roswrap::DefaultMessageCreator::operator()
std::shared_ptr< M > operator()()
Definition: message_event.h:52
test_server.type
type
Definition: test_server.py:210
roswrap::MessageEvent::MessageEvent
MessageEvent(const ConstMessagePtr &message, ros::Time receipt_time)
Definition: message_event.h:123
roswrap::MessageEvent::getReceiptTime
ros::Time getReceiptTime() const
Returns the time at which this message was received.
Definition: message_event.h:182
roswrap::MessageEvent::nonConstWillCopy
bool nonConstWillCopy() const
Definition: message_event.h:184
roswrap::M_string
std::map< std::string, std::string > M_string
Definition: datatypes.h:46
roswrap::MessageEvent::getMessage
std::shared_ptr< M > getMessage() const
Retrieve the message. If M is const, this returns a reference to it. If M is non const and this event...
Definition: message_event.h:159
roswrap::MessageEvent::getConstMessage
const std::shared_ptr< ConstMessage > & getConstMessage() const
Retrieve a const version of the message.
Definition: message_event.h:167
roswrap::MessageEvent::operator<
bool operator<(const MessageEvent< M > &rhs)
Definition: message_event.h:187
roswrap::MessageEvent::getMessageFactory
const CreateFunction & getMessageFactory() const
Definition: message_event.h:212
roswrap::MessageEvent::operator=
void operator=(const MessageEvent< ConstMessage > &rhs)
Definition: message_event.h:148
roswrap::MessageEvent::MessageEvent
MessageEvent(const MessageEvent< void const > &rhs, const CreateFunction &create)
Definition: message_event.h:105
ROS_DEPRECATED
#define ROS_DEPRECATED
Definition: macros.h:39
roswrap::MessageEvent::MessageEvent
MessageEvent(const ConstMessagePtr &message, const std::shared_ptr< M_string > &connection_header, ros::Time receipt_time)
Definition: message_event.h:118
roswrap::MessageEvent::getConnectionHeader
M_string & getConnectionHeader() const
Retrieve the connection header.
Definition: message_event.h:171
roswrap::MessageEvent::getConnectionHeaderPtr
const std::shared_ptr< M_string > & getConnectionHeaderPtr() const
Definition: message_event.h:172
roswrap::MessageEvent::create_
CreateFunction create_
Definition: message_event.h:247
roswrap::MessageEvent::ConstMessagePtr
std::shared_ptr< ConstMessage > ConstMessagePtr
Definition: message_event.h:76
message
def message(msg, *args, **kwargs)
roswrap::MessageEvent::MessageEvent
MessageEvent(const ConstMessagePtr &message, const std::shared_ptr< M_string > &connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction &create)
Definition: message_event.h:128
roswrap::MessageEvent::connection_header_
std::shared_ptr< M_string > connection_header_
Definition: message_event.h:244
ros::DefaultMessageCreator
roswrap::MessageEvent::s_unknown_publisher_string_
static const std::string s_unknown_publisher_string_
Definition: message_event.h:249
roswrap::DefaultMessageCreator
Definition: message_event.h:50
roswrap::MessageEvent::MessageEvent
MessageEvent(const MessageEvent< ConstMessage > &rhs)
Definition: message_event.h:88
roswrap::MessageEvent::copyMessageIfNecessary
std::enable_if<!std::is_void< M2 >::value, std::shared_ptr< M > >::type copyMessageIfNecessary() const
Definition: message_event.h:216
roswrap
Definition: param_modi.cpp:41
roswrap::defaultMessageCreateFunction
ROS_DEPRECATED std::shared_ptr< M > defaultMessageCreateFunction()
Definition: message_event.h:59
roswrap::MessageEvent::getMessageWillCopy
bool getMessageWillCopy() const
Definition: message_event.h:185
roswrap::MessageEvent::MessageEvent
MessageEvent(const MessageEvent< ConstMessage > &rhs, bool nonconst_need_copy)
Definition: message_event.h:99
roswrap::MessageEvent::MessageEvent
MessageEvent(const ConstMessagePtr &message)
Definition: message_event.h:113
roswrap::MessageEvent::CreateFunction
std::function< MessagePtr()> CreateFunction
Definition: message_event.h:77
roswrap::MessageEvent::operator!=
bool operator!=(const MessageEvent< M > &rhs)
Definition: message_event.h:207
roswrap::MessageEvent::ConstMessage
std::add_const< M >::type ConstMessage
Definition: message_event.h:73
roswrap::MessageEvent::message_copy_
MessagePtr message_copy_
Definition: message_event.h:243
ros::Time
roswrap::MessageEvent::init
void init(const ConstMessagePtr &message, const std::shared_ptr< M_string > &connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction &create)
Definition: message_event.h:133
roswrap::MessageEvent::operator=
void operator=(const MessageEvent< Message > &rhs)
Definition: message_event.h:142
roswrap::MessageEvent::MessageEvent
MessageEvent(const MessageEvent< Message > &rhs, bool nonconst_need_copy)
Definition: message_event.h:93
roswrap::MessageEvent::MessagePtr
std::shared_ptr< Message > MessagePtr
Definition: message_event.h:75
roswrap::MessageEvent
Event type for subscriptions, const ros::MessageEvent<M const>& can be used in your callback instead ...
Definition: message_event.h:70
roswrap::MessageEvent::MessageEvent
MessageEvent()
Definition: message_event.h:79
sick_scan_base.h
roswrap::MessageEvent::operator==
bool operator==(const MessageEvent< M > &rhs)
Definition: message_event.h:202
roswrap::MessageEvent::Message
std::remove_const< M >::type Message
Definition: message_event.h:74
roswrap::MessageEvent::getPublisherName
const std::string & getPublisherName() const
Returns the name of the node which published this message.
Definition: message_event.h:177
roswrap::MessageEvent::copyMessageIfNecessary
std::enable_if< std::is_void< M2 >::value, std::shared_ptr< M > >::type copyMessageIfNecessary() const
Definition: message_event.h:236
roswrap::MessageEvent::nonconst_need_copy_
bool nonconst_need_copy_
Definition: message_event.h:246
roswrap::MessageEvent::receipt_time_
ros::Time receipt_time_
Definition: message_event.h:245
ros::Time::now
static Time now()
roswrap::MessageEvent::message_
ConstMessagePtr message_
Definition: message_event.h:241


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