Classes | Functions
ros::topic Namespace Reference

Classes

class  SubscribeHelper

Functions

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.
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, 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, ros::NodeHandle &nh)
 Wait for a single message to arrive on a topic.
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,
NodeHandle &  nh,
ros::Duration  timeout 
)

Wait for a single message to arrive on a topic, with timeout.

Parameters:
M<template> The message type
topicThe topic to subscribe on
nhThe NodeHandle to use to do the subscription
timeoutThe 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 86 of file topic.h.

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.

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

Definition at line 105 of file topic.h.

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.

Parameters:
M<template> The message type
topicThe topic to subscribe on
timeoutThe 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 120 of file topic.h.

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.

Parameters:
M<template> The message type
topicThe topic to subscribe on
nhThe 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 135 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.



roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Thu Jun 6 2019 21:10:06