Template Class TopicHandle_

Class Documentation

template<typename T>
class twist_mux::TopicHandle_

Public Types

typedef int priority_type

Public Functions

TopicHandle_(TopicHandle_&) = delete
TopicHandle_(const TopicHandle_&) = delete
TopicHandle_ &operator=(TopicHandle_&) = delete
TopicHandle_ &operator=(const TopicHandle_&) = delete
inline TopicHandle_(const std::string &name, const std::string &topic, const rclcpp::Duration &timeout, priority_type priority, TwistMux *mux)

TopicHandle_.

Parameters
  • nh – Node handle

  • name – Name identifier

  • topic – Topic name

  • timeout – Timeout to consider that the messages are old; note that initially the message stamp is set to 0.0, so the message has expired

  • priority – Priority of the topic

virtual ~TopicHandle_() = default
inline bool hasExpired() const

hasExpired

Returns

true if the message has expired; false otherwise. If the timeout is set to 0.0, this function always returns false

inline const std::string &getName() const
inline const std::string &getTopic() const
inline const rclcpp::Duration &getTimeout() const
inline const priority_type &getPriority() const

getPriority Priority getter

Returns

Priority

inline const T &getStamp() const
inline const T &getMessage() const

Protected Attributes

std::string name_
std::string topic_
rclcpp::Subscription<T>::SharedPtr subscriber_
rclcpp::Duration timeout_
priority_type priority_
TwistMux *mux_
rclcpp::Time stamp_
T msg_