message_event.h
Go to the documentation of this file.
00001 
00002 /*
00003  * Copyright (C) 2010, Willow Garage, Inc.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *   * Redistributions of source code must retain the above copyright notice,
00008  *     this list of conditions and the following disclaimer.
00009  *   * Redistributions in binary form must reproduce the above copyright
00010  *     notice, this list of conditions and the following disclaimer in the
00011  *     documentation and/or other materials provided with the distribution.
00012  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00013  *     contributors may be used to endorse or promote products derived from
00014  *     this software without specific prior written permission.
00015  *
00016  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026  * POSSIBILITY OF SUCH DAMAGE.
00027  */
00028 
00029 #ifndef ROSCPP_MESSAGE_EVENT_H
00030 #define ROSCPP_MESSAGE_EVENT_H
00031 
00032 #include "ros/forwards.h"
00033 #include "ros/time.h"
00034 #include <ros/assert.h>
00035 #include <ros/message_traits.h>
00036 
00037 #include <boost/type_traits/is_void.hpp>
00038 #include <boost/type_traits/is_base_of.hpp>
00039 #include <boost/type_traits/is_const.hpp>
00040 #include <boost/type_traits/add_const.hpp>
00041 #include <boost/type_traits/remove_const.hpp>
00042 #include <boost/utility/enable_if.hpp>
00043 #include <boost/function.hpp>
00044 #include <boost/make_shared.hpp>
00045 
00046 namespace ros
00047 {
00048 
00049 template<typename M>
00050 struct DefaultMessageCreator
00051 {
00052   boost::shared_ptr<M> operator()()
00053   {
00054     return boost::make_shared<M>();
00055   }
00056 };
00057 
00058 template<typename M>
00059 ROS_DEPRECATED inline boost::shared_ptr<M> defaultMessageCreateFunction()
00060 {
00061   return DefaultMessageCreator<M>()();
00062 }
00063 
00069 template<typename M>
00070 class MessageEvent
00071 {
00072 public:
00073   typedef typename boost::add_const<M>::type ConstMessage;
00074   typedef typename boost::remove_const<M>::type Message;
00075   typedef boost::shared_ptr<Message> MessagePtr;
00076   typedef boost::shared_ptr<ConstMessage> ConstMessagePtr;
00077   typedef boost::function<MessagePtr()> CreateFunction;
00078 
00079   MessageEvent()
00080   : nonconst_need_copy_(true)
00081   {}
00082 
00083   MessageEvent(const MessageEvent<Message>& rhs)
00084   {
00085     *this = rhs;
00086   }
00087 
00088   MessageEvent(const MessageEvent<ConstMessage>& rhs)
00089   {
00090     *this = rhs;
00091   }
00092 
00093   MessageEvent(const MessageEvent<Message>& rhs, bool nonconst_need_copy)
00094   {
00095     *this = rhs;
00096     nonconst_need_copy_ = nonconst_need_copy;
00097   }
00098 
00099   MessageEvent(const MessageEvent<ConstMessage>& rhs, bool nonconst_need_copy)
00100   {
00101     *this = rhs;
00102     nonconst_need_copy_ = nonconst_need_copy;
00103   }
00104 
00105   MessageEvent(const MessageEvent<void const>& rhs, const CreateFunction& create)
00106   {
00107     init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
00108   }
00109 
00113   MessageEvent(const ConstMessagePtr& message)
00114   {
00115     init(message, getConnectionHeader(message.get()), ros::Time::now(), true, ros::DefaultMessageCreator<Message>());
00116   }
00117 
00118   MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
00119   {
00120     init(message, connection_header, receipt_time, true, ros::DefaultMessageCreator<Message>());
00121   }
00122 
00123   MessageEvent(const ConstMessagePtr& message, ros::Time receipt_time)
00124   {
00125     init(message, getConnectionHeader(message.get()), receipt_time, true, ros::DefaultMessageCreator<Message>());
00126   }
00127 
00128   MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
00129   {
00130     init(message, connection_header, receipt_time, nonconst_need_copy, create);
00131   }
00132 
00133   void init(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
00134   {
00135     message_ = message;
00136     connection_header_ = connection_header;
00137     receipt_time_ = receipt_time;
00138     nonconst_need_copy_ = nonconst_need_copy;
00139     create_ = create;
00140   }
00141 
00142   void operator=(const MessageEvent<Message>& rhs)
00143   {
00144     init(boost::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
00145     message_copy_.reset();
00146   }
00147 
00148   void operator=(const MessageEvent<ConstMessage>& rhs)
00149   {
00150     init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
00151     message_copy_.reset();
00152   }
00153 
00159   boost::shared_ptr<M> getMessage() const
00160   {
00161     return copyMessageIfNecessary<M>();
00162   }
00163 
00167   const boost::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
00171   M_string& getConnectionHeader() const { return *connection_header_; }
00172   const boost::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }
00173 
00177   const std::string& getPublisherName() const { return connection_header_ ? (*connection_header_)["callerid"] : s_unknown_publisher_string_; }
00178 
00182   ros::Time getReceiptTime() const { return receipt_time_; }
00183 
00184   bool nonConstWillCopy() const { return nonconst_need_copy_; }
00185   bool getMessageWillCopy() const { return !boost::is_const<M>::value && nonconst_need_copy_; }
00186 
00187   bool operator<(const MessageEvent<M>& rhs)
00188   {
00189     if (message_ != rhs.message_)
00190     {
00191       return message_ < rhs.message_;
00192     }
00193 
00194     if (receipt_time_ != rhs.receipt_time_)
00195     {
00196       return receipt_time_ < rhs.receipt_time_;
00197     }
00198 
00199     return nonconst_need_copy_ < rhs.nonconst_need_copy_;
00200   }
00201 
00202   bool operator==(const MessageEvent<M>& rhs)
00203   {
00204     return message_ = rhs.message_ && receipt_time_ == rhs.receipt_time_ && nonconst_need_copy_ == rhs.nonconst_need_copy_;
00205   }
00206 
00207   bool operator!=(const MessageEvent<M>& rhs)
00208   {
00209     return !(*this == rhs);
00210   }
00211 
00212   const CreateFunction& getMessageFactory() const { return create_; }
00213 
00214 private:
00215   template<typename M2>
00216   typename boost::disable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
00217   {
00218     if (boost::is_const<M>::value || !nonconst_need_copy_)
00219     {
00220       return boost::const_pointer_cast<Message>(message_);
00221     }
00222 
00223     if (message_copy_)
00224     {
00225       return message_copy_;
00226     }
00227 
00228     ROS_ASSERT(create_);
00229     message_copy_ = create_();
00230     *message_copy_ = *message_;
00231 
00232     return message_copy_;
00233   }
00234 
00235   template<typename M2>
00236   typename boost::enable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
00237   {
00238     return boost::const_pointer_cast<Message>(message_);
00239   }
00240 
00241   template<typename T>
00242   boost::shared_ptr<ros::M_string>
00243   getConnectionHeader(T* t, typename boost::enable_if<ros::message_traits::IsMessage<T> >::type*_ = 0) const
00244   {
00245     return t->__connection_header;
00246   }
00247 
00248   template<typename T>
00249   boost::shared_ptr<ros::M_string>
00250   getConnectionHeader(T* t, typename boost::disable_if<ros::message_traits::IsMessage<T> >::type*_ = 0) const
00251   {
00252     return boost::shared_ptr<ros::M_string>();
00253   }
00254 
00255 
00256   ConstMessagePtr message_;
00257   // 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
00258   mutable MessagePtr message_copy_;
00259   boost::shared_ptr<M_string> connection_header_;
00260   ros::Time receipt_time_;
00261   bool nonconst_need_copy_;
00262   CreateFunction create_;
00263 
00264   static const std::string s_unknown_publisher_string_;
00265 };
00266 
00267 template<typename M> const std::string MessageEvent<M>::s_unknown_publisher_string_("unknown_publisher");
00268 
00269 
00270 }
00271 
00272 #endif // ROSCPP_MESSAGE_EVENT_H


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:52