message_event.h
Go to the documentation of this file.
1 
2 /*
3  * Copyright (C) 2010, 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_MESSAGE_EVENT_H
30 #define ROSCPP_MESSAGE_EVENT_H
31 
32 #include "ros/time.h"
33 #include <ros/datatypes.h>
34 #include <ros/message_traits.h>
35 
36 #include <boost/type_traits/is_void.hpp>
37 #include <boost/type_traits/is_base_of.hpp>
38 #include <boost/type_traits/is_const.hpp>
39 #include <boost/type_traits/add_const.hpp>
40 #include <boost/type_traits/remove_const.hpp>
41 #include <boost/utility/enable_if.hpp>
42 #include <boost/function.hpp>
43 #include <boost/make_shared.hpp>
44 
45 namespace ros
46 {
47 
48 template<typename M>
50 {
52  {
53  return boost::make_shared<M>();
54  }
55 };
56 
57 template<typename M>
59 {
60  return DefaultMessageCreator<M>()();
61 }
62 
68 template<typename M>
70 {
71 public:
72  typedef typename boost::add_const<M>::type ConstMessage;
73  typedef typename boost::remove_const<M>::type Message;
76  typedef boost::function<MessagePtr()> CreateFunction;
77 
79  : nonconst_need_copy_(true)
80  {}
81 
83  {
84  *this = rhs;
85  }
86 
88  {
89  *this = rhs;
90  }
91 
92  MessageEvent(const MessageEvent<Message>& rhs, bool nonconst_need_copy)
93  {
94  *this = rhs;
95  nonconst_need_copy_ = nonconst_need_copy;
96  }
97 
98  MessageEvent(const MessageEvent<ConstMessage>& rhs, bool nonconst_need_copy)
99  {
100  *this = rhs;
101  nonconst_need_copy_ = nonconst_need_copy;
102  }
103 
104  MessageEvent(const MessageEvent<void const>& rhs, const CreateFunction& create)
105  {
106  init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
107  }
108 
112  MessageEvent(const ConstMessagePtr& message)
113  {
115  }
116 
117  MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
118  {
119  init(message, connection_header, receipt_time, true, ros::DefaultMessageCreator<Message>());
120  }
121 
122  MessageEvent(const ConstMessagePtr& message, ros::Time receipt_time)
123  {
124  init(message, boost::shared_ptr<M_string>(), receipt_time, true, ros::DefaultMessageCreator<Message>());
125  }
126 
127  MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
128  {
129  init(message, connection_header, receipt_time, nonconst_need_copy, create);
130  }
131 
132  void init(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
133  {
134  message_ = message;
135  connection_header_ = connection_header;
136  receipt_time_ = receipt_time;
137  nonconst_need_copy_ = nonconst_need_copy;
138  create_ = create;
139  }
140 
142  {
143  init(boost::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
144  message_copy_.reset();
145  }
146 
148  {
149  init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
150  message_copy_.reset();
151  }
152 
159  {
160  return copyMessageIfNecessary<M>();
161  }
162 
166  const boost::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
170  M_string& getConnectionHeader() const { return *connection_header_; }
171  const boost::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }
172 
176  const std::string& getPublisherName() const { return connection_header_ ? (*connection_header_)["callerid"] : s_unknown_publisher_string_; }
177 
181  ros::Time getReceiptTime() const { return receipt_time_; }
182 
183  bool nonConstWillCopy() const { return nonconst_need_copy_; }
184  bool getMessageWillCopy() const { return !boost::is_const<M>::value && nonconst_need_copy_; }
185 
186  bool operator<(const MessageEvent<M>& rhs)
187  {
188  if (message_ != rhs.message_)
189  {
190  return message_ < rhs.message_;
191  }
192 
193  if (receipt_time_ != rhs.receipt_time_)
194  {
195  return receipt_time_ < rhs.receipt_time_;
196  }
197 
198  return nonconst_need_copy_ < rhs.nonconst_need_copy_;
199  }
200 
201  bool operator==(const MessageEvent<M>& rhs)
202  {
203  return message_ == rhs.message_ && receipt_time_ == rhs.receipt_time_ && nonconst_need_copy_ == rhs.nonconst_need_copy_;
204  }
205 
206  bool operator!=(const MessageEvent<M>& rhs)
207  {
208  return !(*this == rhs);
209  }
210 
211  const CreateFunction& getMessageFactory() const { return create_; }
212 
213 private:
214  template<typename M2>
215  typename boost::disable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
216  {
217  if (boost::is_const<M>::value || !nonconst_need_copy_)
218  {
219  return boost::const_pointer_cast<Message>(message_);
220  }
221 
222  if (message_copy_)
223  {
224  return message_copy_;
225  }
226 
227  assert(create_);
228  message_copy_ = create_();
229  *message_copy_ = *message_;
230 
231  return message_copy_;
232  }
233 
234  template<typename M2>
235  typename boost::enable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
236  {
237  return boost::const_pointer_cast<Message>(message_);
238  }
239 
240  ConstMessagePtr message_;
241  // 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
242  mutable MessagePtr message_copy_;
246  CreateFunction create_;
247 
248  static const std::string s_unknown_publisher_string_;
249 };
250 
251 template<typename M> const std::string MessageEvent<M>::s_unknown_publisher_string_("unknown_publisher");
252 
253 
254 }
255 
256 #endif // ROSCPP_MESSAGE_EVENT_H
boost::add_const< M >::type ConstMessage
Definition: message_event.h:72
ros::Time getReceiptTime() const
Returns the time at which this message was received.
boost::enable_if< boost::is_void< M2 >, boost::shared_ptr< M > >::type copyMessageIfNecessary() const
MessagePtr message_copy_
boost::disable_if< boost::is_void< M2 >, boost::shared_ptr< M > >::type copyMessageIfNecessary() const
ros::Time receipt_time_
boost::shared_ptr< Message > MessagePtr
Definition: message_event.h:74
bool nonConstWillCopy() const
bool operator==(const MessageEvent< M > &rhs)
const CreateFunction & getMessageFactory() const
M_string & getConnectionHeader() const
Retrieve the connection header.
MessageEvent(const MessageEvent< ConstMessage > &rhs)
Definition: message_event.h:87
bool operator!=(const MessageEvent< M > &rhs)
boost::shared_ptr< M_string > connection_header_
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
void operator=(const MessageEvent< Message > &rhs)
MessageEvent(const MessageEvent< ConstMessage > &rhs, bool nonconst_need_copy)
Definition: message_event.h:98
static const std::string s_unknown_publisher_string_
MessageEvent(const ConstMessagePtr &message, const boost::shared_ptr< M_string > &connection_header, ros::Time receipt_time)
std::map< std::string, std::string > M_string
ConstMessagePtr message_
const std::string & getPublisherName() const
Returns the name of the node which published this message.
const boost::shared_ptr< ConstMessage > & getConstMessage() const
Retrieve a const version of the message.
bool getMessageWillCopy() const
Event type for subscriptions, const ros::MessageEvent<M const>& can be used in your callback instead ...
Definition: message_event.h:69
void operator=(const MessageEvent< ConstMessage > &rhs)
boost::shared_ptr< ConstMessage > ConstMessagePtr
Definition: message_event.h:75
boost::function< MessagePtr()> CreateFunction
Definition: message_event.h:76
MessageEvent(const ConstMessagePtr &message)
boost::shared_ptr< M > operator()()
Definition: message_event.h:51
void init(const ConstMessagePtr &message, const boost::shared_ptr< M_string > &connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction &create)
MessageEvent(const MessageEvent< void const > &rhs, const CreateFunction &create)
CreateFunction create_
#define ROS_DEPRECATED
static Time now()
MessageEvent(const MessageEvent< Message > &rhs, bool nonconst_need_copy)
Definition: message_event.h:92
ROS_DEPRECATED boost::shared_ptr< M > defaultMessageCreateFunction()
Definition: message_event.h:58
MessageEvent(const ConstMessagePtr &message, ros::Time receipt_time)
MessageEvent(const MessageEvent< Message > &rhs)
Definition: message_event.h:82
boost::remove_const< M >::type Message
Definition: message_event.h:73
MessageEvent(const ConstMessagePtr &message, const boost::shared_ptr< M_string > &connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction &create)
boost::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...


roscpp_traits
Author(s): Josh Faust
autogenerated on Sat Apr 6 2019 02:52:23