mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
timer.hpp
1 #ifndef MRS_TIMER_HPP
2 #define MRS_TIMER_HPP
3 
4 // | ------------------------ ROSTimer ------------------------ |
5 
6 /* ROSTimer constructors //{ */
7 
8 // duration + oneshot + autostart
9 #include <chrono>
10 #include <mutex>
11 template <class ObjectType>
12 ROSTimer::ROSTimer(const ros::NodeHandle& nh, const ros::Duration& duration, void (ObjectType::*const callback)(const ros::TimerEvent&),
13  ObjectType* const obj, const bool oneshot, const bool autostart) {
14 
15  this->timer_ = std::make_unique<ros::Timer>(nh.createTimer(duration, callback, obj, oneshot, autostart));
16 }
17 
18 // rate + oneshot + autostart
19 template <class ObjectType>
20 ROSTimer::ROSTimer(const ros::NodeHandle& nh, const ros::Rate& rate, void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj,
21  const bool oneshot, const bool autostart) {
22 
23  this->timer_ = std::make_unique<ros::Timer>(nh.createTimer(rate, callback, obj, oneshot, autostart));
24 }
25 
26 //}
27 
28 // | ----------------------- ThreadTimer ---------------------- |
29 
30 /* class ThreadTimer::Impl //{ */
31 
33 public:
34  Impl(const std::function<void(const ros::TimerEvent&)>& callback, const ros::Duration& delay_dur, const bool oneshot);
35  ~Impl();
36 
37  void start();
38  void stop();
39  void setPeriod(const ros::Duration& duration, const bool reset = true);
40  void setCallback(const std::function<void(const ros::TimerEvent&)>& callback);
41 
42  friend class ThreadTimer;
43 
44  // to keep rule of five since we have a custom destructor
45  Impl(const Impl&) = delete;
46  Impl(Impl&&) = delete;
47  Impl& operator=(const Impl&) = delete;
48  Impl& operator=(Impl&&) = delete;
49 
50 private:
51  std::thread thread_;
52  std::function<void(const ros::TimerEvent&)> callback_;
53 
54  bool oneshot_;
55 
56  bool breakableSleep(const ros::Time& until);
57  void threadFcn();
58 
59  std::mutex mutex_wakeup_;
60  std::condition_variable wakeup_cond_;
61  std::recursive_mutex mutex_state_;
62  bool running_;
63  ros::Duration delay_dur_;
64  bool ending_;
65  ros::Time next_expected_;
66  ros::Time last_expected_;
67  ros::Time last_real_;
68 
69 };
70 
71 //}
72 
73 /* ThreadTimer constructors and destructors//{ */
74 
75 template <class ObjectType>
76 ThreadTimer::ThreadTimer([[maybe_unused]] const ros::NodeHandle& nh, const ros::Rate& rate, void (ObjectType::*const callback)(const ros::TimerEvent&),
77  ObjectType* const obj, const bool oneshot, const bool autostart)
78  : ThreadTimer(nh, rate.expectedCycleTime(), callback, obj, oneshot, autostart)
79 {
80 }
81 
82 template <class ObjectType>
83 ThreadTimer::ThreadTimer([[maybe_unused]] const ros::NodeHandle& nh, const ros::Duration& duration,
84  void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj, bool oneshot, const bool autostart)
85 {
86  const auto cbk = std::bind(callback, obj, std::placeholders::_1);
87  if (duration == ros::Duration(0))
88  oneshot = true;
89  this->impl_ = std::make_unique<Impl>(cbk, duration, oneshot);
90  if (autostart)
91  this->impl_->start();
92 }
93 
94 //}
95 
96 #endif // MRS_TIMER_HPP
ThreadTimer::Impl
Definition: timer.hpp:32