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/time.h"
00033 #include <ros/datatypes.h>
00034 #include <ros/message_traits.h>
00035 
00036 #include <boost/type_traits/is_void.hpp>
00037 #include <boost/type_traits/is_base_of.hpp>
00038 #include <boost/type_traits/is_const.hpp>
00039 #include <boost/type_traits/add_const.hpp>
00040 #include <boost/type_traits/remove_const.hpp>
00041 #include <boost/utility/enable_if.hpp>
00042 #include <boost/function.hpp>
00043 #include <boost/make_shared.hpp>
00044 
00045 namespace ros
00046 {
00047 
00048 template<typename M>
00049 struct DefaultMessageCreator
00050 {
00051   boost::shared_ptr<M> operator()()
00052   {
00053     return boost::make_shared<M>();
00054   }
00055 };
00056 
00057 template<typename M>
00058 ROS_DEPRECATED inline boost::shared_ptr<M> defaultMessageCreateFunction()
00059 {
00060   return DefaultMessageCreator<M>()();
00061 }
00062 
00068 template<typename M>
00069 class MessageEvent
00070 {
00071 public:
00072   typedef typename boost::add_const<M>::type ConstMessage;
00073   typedef typename boost::remove_const<M>::type Message;
00074   typedef boost::shared_ptr<Message> MessagePtr;
00075   typedef boost::shared_ptr<ConstMessage> ConstMessagePtr;
00076   typedef boost::function<MessagePtr()> CreateFunction;
00077 
00078   MessageEvent()
00079   : nonconst_need_copy_(true)
00080   {}
00081 
00082   MessageEvent(const MessageEvent<Message>& rhs)
00083   {
00084     *this = rhs;
00085   }
00086 
00087   MessageEvent(const MessageEvent<ConstMessage>& rhs)
00088   {
00089     *this = rhs;
00090   }
00091 
00092   MessageEvent(const MessageEvent<Message>& rhs, bool nonconst_need_copy)
00093   {
00094     *this = rhs;
00095     nonconst_need_copy_ = nonconst_need_copy;
00096   }
00097 
00098   MessageEvent(const MessageEvent<ConstMessage>& rhs, bool nonconst_need_copy)
00099   {
00100     *this = rhs;
00101     nonconst_need_copy_ = nonconst_need_copy;
00102   }
00103 
00104   MessageEvent(const MessageEvent<void const>& rhs, const CreateFunction& create)
00105   {
00106     init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
00107   }
00108 
00112   MessageEvent(const ConstMessagePtr& message)
00113   {
00114     init(message, boost::shared_ptr<M_string>(), ros::Time::now(), true, ros::DefaultMessageCreator<Message>());
00115   }
00116 
00117   MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
00118   {
00119     init(message, connection_header, receipt_time, true, ros::DefaultMessageCreator<Message>());
00120   }
00121 
00122   MessageEvent(const ConstMessagePtr& message, ros::Time receipt_time)
00123   {
00124     init(message, boost::shared_ptr<M_string>(), receipt_time, true, ros::DefaultMessageCreator<Message>());
00125   }
00126 
00127   MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
00128   {
00129     init(message, connection_header, receipt_time, nonconst_need_copy, create);
00130   }
00131 
00132   void init(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
00133   {
00134     message_ = message;
00135     connection_header_ = connection_header;
00136     receipt_time_ = receipt_time;
00137     nonconst_need_copy_ = nonconst_need_copy;
00138     create_ = create;
00139   }
00140 
00141   void operator=(const MessageEvent<Message>& rhs)
00142   {
00143     init(boost::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
00144     message_copy_.reset();
00145   }
00146 
00147   void operator=(const MessageEvent<ConstMessage>& rhs)
00148   {
00149     init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
00150     message_copy_.reset();
00151   }
00152 
00158   boost::shared_ptr<M> getMessage() const
00159   {
00160     return copyMessageIfNecessary<M>();
00161   }
00162 
00166   const boost::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
00170   M_string& getConnectionHeader() const { return *connection_header_; }
00171   const boost::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }
00172 
00176   const std::string& getPublisherName() const { return connection_header_ ? (*connection_header_)["callerid"] : s_unknown_publisher_string_; }
00177 
00181   ros::Time getReceiptTime() const { return receipt_time_; }
00182 
00183   bool nonConstWillCopy() const { return nonconst_need_copy_; }
00184   bool getMessageWillCopy() const { return !boost::is_const<M>::value && nonconst_need_copy_; }
00185 
00186   bool operator<(const MessageEvent<M>& rhs)
00187   {
00188     if (message_ != rhs.message_)
00189     {
00190       return message_ < rhs.message_;
00191     }
00192 
00193     if (receipt_time_ != rhs.receipt_time_)
00194     {
00195       return receipt_time_ < rhs.receipt_time_;
00196     }
00197 
00198     return nonconst_need_copy_ < rhs.nonconst_need_copy_;
00199   }
00200 
00201   bool operator==(const MessageEvent<M>& rhs)
00202   {
00203     return message_ = rhs.message_ && receipt_time_ == rhs.receipt_time_ && nonconst_need_copy_ == rhs.nonconst_need_copy_;
00204   }
00205 
00206   bool operator!=(const MessageEvent<M>& rhs)
00207   {
00208     return !(*this == rhs);
00209   }
00210 
00211   const CreateFunction& getMessageFactory() const { return create_; }
00212 
00213 private:
00214   template<typename M2>
00215   typename boost::disable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
00216   {
00217     if (boost::is_const<M>::value || !nonconst_need_copy_)
00218     {
00219       return boost::const_pointer_cast<Message>(message_);
00220     }
00221 
00222     if (message_copy_)
00223     {
00224       return message_copy_;
00225     }
00226 
00227     assert(create_);
00228     message_copy_ = create_();
00229     *message_copy_ = *message_;
00230 
00231     return message_copy_;
00232   }
00233 
00234   template<typename M2>
00235   typename boost::enable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
00236   {
00237     return boost::const_pointer_cast<Message>(message_);
00238   }
00239 
00240   ConstMessagePtr message_;
00241   // 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
00242   mutable MessagePtr message_copy_;
00243   boost::shared_ptr<M_string> connection_header_;
00244   ros::Time receipt_time_;
00245   bool nonconst_need_copy_;
00246   CreateFunction create_;
00247 
00248   static const std::string s_unknown_publisher_string_;
00249 };
00250 
00251 template<typename M> const std::string MessageEvent<M>::s_unknown_publisher_string_("unknown_publisher");
00252 
00253 
00254 }
00255 
00256 #endif // ROSCPP_MESSAGE_EVENT_H


roscpp_traits
Author(s): Josh Faust
autogenerated on Sat Jun 8 2019 20:30:26