$search

ros::topic Namespace Reference

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.
ROSCPP_DECL void waitForMessageImpl (SubscribeOptions &ops, const boost::function< bool(void)> &ready_pred, NodeHandle &nh, ros::Duration timeout)
 Internal method, do not use.

Function Documentation

template<class M >
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.

Parameters:
M <template> The message type
topic The topic to subscribe on
nh The NodeHandle to use to do the subscription
Returns:
The message. Empty boost::shared_ptr if waitForMessage is interrupted by the node shutting down

Definition at line 130 of file topic.h.

template<class M >
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.

Parameters:
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
Returns:
The message. Empty boost::shared_ptr if waitForMessage is interrupted by the node shutting down

Definition at line 115 of file topic.h.

template<class M >
boost::shared_ptr<M const> ros::topic::waitForMessage ( const std::string &  topic  )  [inline]

Wait for a single message to arrive on a topic.

Parameters:
M <template> The message type
topic The topic to subscribe on
Returns:
The message. Empty boost::shared_ptr if waitForMessage is interrupted by the node shutting down

Definition at line 100 of file topic.h.

template<class M >
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.

Parameters:
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
Returns:
The message. Empty boost::shared_ptr if waitForMessage is interrupted by the node shutting down

Definition at line 81 of file topic.h.

void ros::topic::waitForMessageImpl ( SubscribeOptions &  ops,
const boost::function< bool(void)> &  ready_pred,
NodeHandle &  nh,
ros::Duration  timeout 
)

Internal method, do not use.

Definition at line 43 of file topic.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Mar 2 13:23:33 2013