Classes | |
class | SubscribeHelper |
Functions | |
template<class M > | |
boost::shared_ptr< M const > | 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 > | 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 > | waitForMessage (const std::string &topic) |
Wait for a single message to arrive on a topic. | |
template<class M > | |
boost::shared_ptr< M const > | waitForMessage (const std::string &topic, NodeHandle &nh, ros::Duration timeout) |
Wait for a single message to arrive on a topic, with timeout. | |
void | waitForMessageImpl (SubscribeOptions &ops, const boost::function< bool(void)> &ready_pred, NodeHandle &nh, ros::Duration timeout) |
Internal method, do not use. |
boost::shared_ptr<M const> ros::topic::waitForMessage | ( | const std::string & | topic, | |
ros::NodeHandle & | nh | |||
) | [inline] |
Wait for a single message to arrive on a topic.
M | <template> The message type | |
topic | The topic to subscribe on | |
nh | The NodeHandle to use to do the subscription |
boost::shared_ptr<M const> ros::topic::waitForMessage | ( | const std::string & | topic, | |
ros::Duration | timeout | |||
) | [inline] |
Wait for a single message to arrive on a topic, with timeout.
M | <template> The message type | |
topic | The topic to subscribe on | |
timeout | The amount of time to wait before returning if no message is received |
boost::shared_ptr<M const> ros::topic::waitForMessage | ( | const std::string & | topic | ) | [inline] |
boost::shared_ptr<M const> ros::topic::waitForMessage | ( | const std::string & | topic, | |
NodeHandle & | nh, | |||
ros::Duration | timeout | |||
) | [inline] |
Wait for a single message to arrive on a topic, with timeout.
M | <template> The message type | |
topic | The topic to subscribe on | |
nh | The NodeHandle to use to do the subscription | |
timeout | The amount of time to wait before returning if no message is received |