Class Subscriber

Class Documentation

class Subscriber

Public Types

enum DIAGNOSTIC_FLAGS

Values:

enumerator DIAG_CONNECTION
enumerator DIAG_MSG_COUNT
enumerator DIAG_TIMEOUT
enumerator DIAG_LATENCY
enumerator DIAG_RATE
enumerator DIAG_ALL
enumerator DIAG_MOST

Public Functions

inline Subscriber()
template<class M, class T>
inline Subscriber(rclcpp::Node &nh, const std::string &topic, uint32_t queue_size, void (T::* fp)(const std::shared_ptr<M const>&), T *obj, const rclcpp::QoS &transport_hints = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)), const rclcpp::SubscriptionOptions sub_options = rclcpp::SubscriptionOptions())
template<class M>
inline Subscriber(rclcpp::Node &nh, const std::string &topic, uint32_t queue_size, const std::function<void(const std::shared_ptr<M const>&)> &callback, const rclcpp::QoS &transport_hints = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)), const rclcpp::SubscriptionOptions sub_options = rclcpp::SubscriptionOptions())
template<class M, class T>
Subscriber(rclcpp::Node &nh, const std::string &topic, uint32_t queue_size, void (T::* fp)(const std::unique_ptr<M const>&), T *obj, const rclcpp::QoS &transport_hints = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)), const rclcpp::SubscriptionOptions sub_options = rclcpp::SubscriptionOptions())
template<class M>
Subscriber(rclcpp::Node &nh, const std::string &topic, uint32_t queue_size, const std::function<void(const std::unique_ptr<M const>&)> &callback, const rclcpp::QoS &transport_hints = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)), const rclcpp::SubscriptionOptions sub_options = rclcpp::SubscriptionOptions())
template<class M>
inline Subscriber(rclcpp::Node &nh, const std::string &topic, std::shared_ptr<M const> *dest, const rclcpp::QoS &transport_hints = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)), const rclcpp::SubscriptionOptions sub_options = rclcpp::SubscriptionOptions())
inline Subscriber &operator=(const Subscriber &other)
inline void resetStatistics()
inline const std::string &unmappedTopic() const
inline int numPublishers() const
inline int messageCount() const
inline rclcpp::Duration age(const rclcpp::Time &now = rclcpp::Time(0, 0, RCL_ROS_TIME)) const
inline double ageSeconds(const rclcpp::Time &now = rclcpp::Time(0, 0, RCL_ROS_TIME)) const
inline double ageMilliseconds(const rclcpp::Time &now = rclcpp::Time(0, 0, RCL_ROS_TIME)) const
inline rclcpp::Duration meanLatency() const
inline rclcpp::Duration minLatency() const
inline rclcpp::Duration maxLatency() const
inline double meanLatencyMicroseconds() const
inline double minLatencyMicroseconds() const
inline double maxLatencyMicroseconds() const
inline double meanFrequencyHz() const
inline rclcpp::Duration meanPeriod() const
inline rclcpp::Duration minPeriod() const
inline rclcpp::Duration maxPeriod() const
inline double meanPeriodMilliseconds() const
inline double minPeriodMilliseconds() const
inline double maxPeriodMilliseconds() const
inline void setTimeout(const rclcpp::Duration &time_out)
inline void setTimeout(const double time_out)
inline bool blockTimeouts(bool block)
inline bool timeoutsBlocked() const
inline bool timeoutEnabled() const
inline rclcpp::Duration timeout() const
inline double timeoutMilliseconds() const
inline bool inTimeout()
inline int timeoutCount()
inline void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)