#include <subscriber.h>
|
ros::Duration | age (const ros::Time &now=ros::TIME_MIN) const |
|
double | ageMilliseconds (const ros::Time &now=ros::TIME_MIN) const |
|
double | ageSeconds (const ros::Time &now=ros::TIME_MIN) const |
|
void | appendDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags) |
|
bool | blockTimeouts (bool block) |
|
bool | inTimeout () |
|
const std::string & | mappedTopic () const |
|
ros::Duration | maxLatency () const |
|
double | maxLatencyMicroseconds () const |
|
ros::Duration | maxPeriod () const |
|
double | maxPeriodMilliseconds () const |
|
double | meanFrequencyHz () const |
|
ros::Duration | meanLatency () const |
|
double | meanLatencyMicroseconds () const |
|
ros::Duration | meanPeriod () const |
|
double | meanPeriodMilliseconds () const |
|
int | messageCount () const |
|
ros::Duration | minLatency () const |
|
double | minLatencyMicroseconds () const |
|
ros::Duration | minPeriod () const |
|
double | minPeriodMilliseconds () const |
|
int | numPublishers () const |
|
Subscriber & | operator= (const Subscriber &other) |
|
void | resetStatistics () |
|
void | setTimeout (const ros::Duration &time_out) |
|
void | setTimeout (const double time_out) |
|
| Subscriber () |
|
template<class M , class T > |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M > |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M > |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, boost::shared_ptr< M const > *dest, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
ros::Duration | timeout () const |
|
int | timeoutCount () |
|
bool | timeoutEnabled () const |
|
double | timeoutMilliseconds () const |
|
void | timeoutParam (const ros::NodeHandle &nh, const std::string ¶meter_name, const double default_value) |
|
bool | timeoutsBlocked () const |
|
const std::string & | unmappedTopic () const |
|
Definition at line 61 of file subscriber.h.
Enumerator |
---|
DIAG_CONNECTION |
|
DIAG_MSG_COUNT |
|
DIAG_TIMEOUT |
|
DIAG_LATENCY |
|
DIAG_RATE |
|
DIAG_ALL |
|
DIAG_MOST |
|
Definition at line 177 of file subscriber.h.
swri::Subscriber::Subscriber |
( |
| ) |
|
|
inline |
template<class M , class T >
bool swri::Subscriber::blockTimeouts |
( |
bool |
block | ) |
|
|
inline |
bool swri::Subscriber::inTimeout |
( |
| ) |
|
|
inline |
const std::string & swri::Subscriber::mappedTopic |
( |
| ) |
const |
|
inline |
double swri::Subscriber::maxLatencyMicroseconds |
( |
| ) |
const |
|
inline |
double swri::Subscriber::maxPeriodMilliseconds |
( |
| ) |
const |
|
inline |
double swri::Subscriber::meanFrequencyHz |
( |
| ) |
const |
|
inline |
double swri::Subscriber::meanLatencyMicroseconds |
( |
| ) |
const |
|
inline |
double swri::Subscriber::meanPeriodMilliseconds |
( |
| ) |
const |
|
inline |
int swri::Subscriber::messageCount |
( |
| ) |
const |
|
inline |
double swri::Subscriber::minLatencyMicroseconds |
( |
| ) |
const |
|
inline |
double swri::Subscriber::minPeriodMilliseconds |
( |
| ) |
const |
|
inline |
int swri::Subscriber::numPublishers |
( |
| ) |
const |
|
inline |
void swri::Subscriber::resetStatistics |
( |
| ) |
|
|
inline |
void swri::Subscriber::setTimeout |
( |
const ros::Duration & |
time_out | ) |
|
|
inline |
void swri::Subscriber::setTimeout |
( |
const double |
time_out | ) |
|
|
inline |
int swri::Subscriber::timeoutCount |
( |
| ) |
|
|
inline |
bool swri::Subscriber::timeoutEnabled |
( |
| ) |
const |
|
inline |
double swri::Subscriber::timeoutMilliseconds |
( |
| ) |
const |
|
inline |
void swri::Subscriber::timeoutParam |
( |
const ros::NodeHandle & |
nh, |
|
|
const std::string & |
parameter_name, |
|
|
const double |
default_value |
|
) |
| |
|
inline |
bool swri::Subscriber::timeoutsBlocked |
( |
| ) |
const |
|
inline |
const std::string & swri::Subscriber::unmappedTopic |
( |
| ) |
const |
|
inline |
The documentation for this class was generated from the following file: