27 using timeout_id_t = size_t;
28 using callback_t = std::function<void(
const rclcpp::Time&)>;
33 TimeoutManager(
const std::shared_ptr<rclcpp::Node>& node,
const rclcpp::Rate& update_rate);
35 timeout_id_t registerNew(
const rclcpp::Duration& timeout,
const callback_t& callback,
const rclcpp::Time& last_reset,
const bool oneshot =
false,
36 const bool autostart =
true);
38 void reset(
const timeout_id_t
id,
const rclcpp::Time& time);
40 void pause(
const timeout_id_t
id);
42 void start(
const timeout_id_t
id,
const rclcpp::Time& time);
48 void change(
const timeout_id_t
id,
const rclcpp::Duration& timeout,
const callback_t& callback,
const rclcpp::Time& last_reset,
const bool oneshot =
false,
49 const bool autostart =
true);
51 rclcpp::Time lastReset(
const timeout_id_t
id);
53 bool started(
const timeout_id_t
id);
64 rclcpp::Duration timeout;
65 rclcpp::Time last_reset;
66 rclcpp::Time last_callback;
71 void main_timer_callback();
75 std::recursive_mutex m_mtx;
76 timeout_id_t m_last_id;
77 std::vector<timeout_info_t> m_timeouts;
79 std::shared_ptr<rclcpp::Node> node_;
81 rclcpp::CallbackGroup::SharedPtr cb_grp_;
83 std::shared_ptr<TimerType> m_main_timer;
rclcpp::Timer wrapper. The interface is the same as with rclcpp::Timer, except for the initialization...
Definition timer_handler.h:94
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24