7 #ifndef TIMEOUT_MANAGER_H
8 #define TIMEOUT_MANAGER_H
23 using timeout_id_t = size_t;
24 using callback_t = std::function<void(
const ros::Time&)>;
33 TimeoutManager(
const ros::NodeHandle& nh,
const ros::Rate& update_rate);
35 timeout_id_t registerNew(
const ros::Duration& timeout,
const callback_t& callback,
const ros::Time& last_reset = ros::Time::now(),
const bool oneshot =
false,
const bool autostart =
true);
37 void reset(
const timeout_id_t
id,
const ros::Time& time = ros::Time::now());
39 void pause(
const timeout_id_t
id);
41 void start(
const timeout_id_t
id,
const ros::Time& time = ros::Time::now());
45 void startAll(
const ros::Time& time = ros::Time::now());
47 void change(
const timeout_id_t
id,
const ros::Duration& timeout,
const callback_t& callback,
const ros::Time& last_reset = ros::Time::now(),
const bool oneshot =
false,
const bool autostart =
true);
49 ros::Time lastReset(
const timeout_id_t
id);
51 bool started(
const timeout_id_t
id);
62 ros::Duration timeout;
64 ros::Time last_callback;
69 void main_timer_callback([[maybe_unused]]
const ros::TimerEvent& evt);
73 std::recursive_mutex m_mtx;
74 timeout_id_t m_last_id;
75 std::vector<timeout_info_t> m_timeouts;
77 ros::Timer m_main_timer;
85 #endif // TIMEOUT_MANAGER_H