$search
#include "common.h"#include "node_handle.h"#include "ros/forwards.h"#include "ros/publisher.h"#include "ros/subscriber.h"#include "ros/service_server.h"#include "ros/service_client.h"#include "ros/timer.h"#include "ros/rate.h"#include "ros/wall_timer.h"#include "ros/advertise_options.h"#include "ros/advertise_service_options.h"#include "ros/subscribe_options.h"#include "ros/service_client_options.h"#include "ros/timer_options.h"#include "ros/wall_timer_options.h"#include "ros/spinner.h"#include "ros/init.h"#include <boost/bind.hpp>#include <XmlRpcValue.h>#include <boost/shared_ptr.hpp>

Go to the source code of this file.
Classes | |
| class | ros::topic::SubscribeHelper< M > |
Namespaces | |
| namespace | ros |
| namespace | ros::topic |
Functions | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |