Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #ifndef ROSCPP_TOPIC_H
00036 #define ROSCPP_TOPIC_H
00037 
00038 #include "common.h"
00039 #include "node_handle.h"
00040 #include <boost/shared_ptr.hpp>
00041 
00042 namespace ros
00043 {
00044 namespace topic
00045 {
00046 
00050 ROSCPP_DECL void waitForMessageImpl(SubscribeOptions& ops, const boost::function<bool(void)>& ready_pred, NodeHandle& nh, ros::Duration timeout);
00051 
00052 template<class M>
00053 class SubscribeHelper
00054 {
00055 public:
00056   typedef boost::shared_ptr<M const> MConstPtr;
00057   void callback(const MConstPtr& message)
00058   {
00059     message_ = message;
00060   }
00061 
00062   bool hasMessage()
00063   {
00064     return static_cast<bool>(message_);
00065   }
00066 
00067   MConstPtr getMessage()
00068   {
00069     return message_;
00070   }
00071 
00072 private:
00073   MConstPtr message_;
00074 };
00075 
00085 template<class M>
00086 boost::shared_ptr<M const> waitForMessage(const std::string& topic, NodeHandle& nh, ros::Duration timeout)
00087 {
00088   SubscribeHelper<M> helper;
00089   SubscribeOptions ops;
00090   ops.template init<M>(topic, 1, boost::bind(&SubscribeHelper<M>::callback, &helper, _1));
00091 
00092   waitForMessageImpl(ops, boost::bind(&SubscribeHelper<M>::hasMessage, &helper), nh, timeout);
00093 
00094   return helper.getMessage();
00095 }
00096 
00104 template<class M>
00105 boost::shared_ptr<M const> waitForMessage(const std::string& topic)
00106 {
00107   ros::NodeHandle nh;
00108   return waitForMessage<M>(topic, nh, ros::Duration());
00109 }
00110 
00119 template<class M>
00120 boost::shared_ptr<M const> waitForMessage(const std::string& topic, ros::Duration timeout)
00121 {
00122   ros::NodeHandle nh;
00123   return waitForMessage<M>(topic, nh, timeout);
00124 }
00125 
00134 template<class M>
00135 boost::shared_ptr<M const> waitForMessage(const std::string& topic, ros::NodeHandle& nh)
00136 {
00137   return waitForMessage<M>(topic, nh, ros::Duration());
00138 }
00139 
00140 } 
00141 } 
00142 
00143 #endif // ROSCPP_TOPIC_H
 
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47