mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
timeout_manager.h
Go to the documentation of this file.
1 // clang: MatousFormat
7 #ifndef TIMEOUT_MANAGER_H
8 #define TIMEOUT_MANAGER_H
9 
10 #include <ros/ros.h>
11 
12 namespace mrs_lib
13 {
14  /* TimeoutManager class //{ */
20  {
21  public:
22  // | ---------------------- public types ---------------------- |
23  using timeout_id_t = size_t;
24  using callback_t = std::function<void(const ros::Time&)>;
25 
26  public:
27  // | --------------------- public methods --------------------- |
28 
33  TimeoutManager(const ros::NodeHandle& nh, const ros::Rate& update_rate);
34 
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);
36 
37  void reset(const timeout_id_t id, const ros::Time& time = ros::Time::now());
38 
39  void pause(const timeout_id_t id);
40 
41  void start(const timeout_id_t id, const ros::Time& time = ros::Time::now());
42 
43  void pauseAll();
44 
45  void startAll(const ros::Time& time = ros::Time::now());
46 
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);
48 
49  ros::Time lastReset(const timeout_id_t id);
50 
51  bool started(const timeout_id_t id);
52 
53  /* implementation details //{ */
54 
55  private:
56  // | ---------------------- private types --------------------- |
57  struct timeout_info_t
58  {
59  bool oneshot;
60  bool started;
61  callback_t callback;
62  ros::Duration timeout;
63  ros::Time last_reset;
64  ros::Time last_callback;
65  };
66 
67  private:
68  // | --------------------- private methods -------------------- |
69  void main_timer_callback([[maybe_unused]] const ros::TimerEvent& evt);
70 
71  private:
72  // | ------------------------- members ------------------------ |
73  std::recursive_mutex m_mtx;
74  timeout_id_t m_last_id;
75  std::vector<timeout_info_t> m_timeouts;
76 
77  ros::Timer m_main_timer;
78 
79  //}
80 
81  };
82  //}
83 }
84 
85 #endif // TIMEOUT_MANAGER_H
mrs_lib::TimeoutManager::TimeoutManager
TimeoutManager(const ros::NodeHandle &nh, const ros::Rate &update_rate)
TODO.
Definition: timeout_manager.cpp:6
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::TimeoutManager
TODO.
Definition: timeout_manager.h:19