#include "common.h"
#include "node_handle.h"
#include <boost/shared_ptr.hpp>
Go to the source code of this file.
|
template<class M > |
boost::shared_ptr< M const > | ros::topic::waitForMessage (const std::string &topic, NodeHandle &nh, ros::Duration timeout) |
| Wait for a single message to arrive on a topic, with timeout. More...
|
|
template<class M > |
boost::shared_ptr< M const > | ros::topic::waitForMessage (const std::string &topic) |
| Wait for a single message to arrive on a topic. More...
|
|
template<class M > |
boost::shared_ptr< M const > | ros::topic::waitForMessage (const std::string &topic, ros::Duration timeout) |
| Wait for a single message to arrive on a topic, with timeout. More...
|
|
template<class M > |
boost::shared_ptr< M const > | ros::topic::waitForMessage (const std::string &topic, ros::NodeHandle &nh) |
| Wait for a single message to arrive on a topic. More...
|
|
ROSCPP_DECL void | ros::topic::waitForMessageImpl (SubscribeOptions &ops, const boost::function< bool(void)> &ready_pred, NodeHandle &nh, ros::Duration timeout) |
| Internal method, do not use. More...
|
|
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:26