mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
timer.h
1 #ifndef MRS_TIMER_H
2 #define MRS_TIMER_H
3 
4 #include <ros/ros.h>
5 #include <thread>
6 #include <mutex>
7 #include <condition_variable>
8 #include <atomic>
9 
10 namespace mrs_lib
11 {
21  class MRSTimer
22  {
23  public:
24  using callback_t = std::function<void(const ros::TimerEvent&)>;
25 
29  virtual void stop() = 0;
30 
34  virtual void start() = 0;
35 
42  virtual void setPeriod(const ros::Duration& duration, const bool reset = true) = 0;
43 
51  virtual void setCallback(const std::function<void(const ros::TimerEvent&)>& callback) = 0;
52 
58  virtual bool running() = 0;
59 
60  virtual ~MRSTimer() = default;
61  MRSTimer(const MRSTimer&) = default;
62  MRSTimer(MRSTimer&&) = default;
63  MRSTimer& operator=(const MRSTimer&) = default;
64  MRSTimer& operator=(MRSTimer&&) = default;
65 
66  protected:
67  MRSTimer() = default;
68  };
69 
70  // | ------------------------ ROSTimer ------------------------ |
71 
72  /* class ROSTimer //{ */
73 
77  class ROSTimer : public MRSTimer {
78  public:
79  ROSTimer();
80 
92  template <class ObjectType>
93  ROSTimer(const ros::NodeHandle& nh, const ros::Rate& rate, void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj,
94  const bool oneshot = false, const bool autostart = true);
95 
107  template <class ObjectType>
108  ROSTimer(const ros::NodeHandle& nh, const ros::Duration& duration, void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj,
109  const bool oneshot = false, const bool autostart = true);
110 
114  virtual void stop() override;
115 
119  virtual void start() override;
120 
127  virtual void setPeriod(const ros::Duration& duration, const bool reset = true) override;
128 
136  virtual void setCallback(const std::function<void(const ros::TimerEvent&)>& callback) override;
137 
143  virtual bool running() override;
144 
145  virtual ~ROSTimer() override {stop();};
146  // to keep rule of five since we have a custom destructor
147  ROSTimer(const ROSTimer&) = delete;
148  ROSTimer(ROSTimer&&) = delete;
149  ROSTimer& operator=(const ROSTimer&) = delete;
150  ROSTimer& operator=(ROSTimer&&) = delete;
151 
152  private:
153  std::mutex mutex_timer_;
154 
155  std::unique_ptr<ros::Timer> timer_;
156  };
157 
158  //}
159 
160  // | ----------------------- ThreadTimer ---------------------- |
161 
162  /* class ThreadTimer //{ */
163 
167  class ThreadTimer : public MRSTimer {
168 
169  public:
170  ThreadTimer();
171 
183  template <class ObjectType>
184  ThreadTimer(const ros::NodeHandle& nh, const ros::Rate& rate, void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj,
185  const bool oneshot = false, const bool autostart = true);
186 
198  template <class ObjectType>
199  ThreadTimer(const ros::NodeHandle& nh, const ros::Duration& duration, void (ObjectType::*const callback)(const ros::TimerEvent&), ObjectType* const obj,
200  bool oneshot = false, const bool autostart = true);
201 
207  virtual void stop() override;
208 
216  virtual void start() override;
217 
226  virtual void setPeriod(const ros::Duration& duration, const bool reset = true) override;
227 
235  virtual void setCallback(const std::function<void(const ros::TimerEvent&)>& callback) override;
236 
242  virtual bool running() override;
243 
249  virtual ~ThreadTimer() override {stop();};
250  // to keep rule of five since we have a custom destructor
251  ThreadTimer(const ThreadTimer&) = delete;
252  ThreadTimer(ThreadTimer&&) = delete;
253  ThreadTimer& operator=(const ThreadTimer&) = delete;
254  ThreadTimer& operator=(ThreadTimer&&) = delete;
255 
256  private:
257  class Impl;
258 
259  std::unique_ptr<Impl> impl_;
260 
261  }; // namespace mrs_lib
262 
263  //}
264 
265 #include <mrs_lib/impl/timer.hpp>
266 
267 } // namespace mrs_lib
268 
269 #endif // MRS_TIMER_H
mrs_lib::ThreadTimer::~ThreadTimer
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition: timer.h:249
mrs_lib::ThreadTimer::setCallback
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback) override
change the callback method
Definition: timer.cpp:107
mrs_lib::ThreadTimer::stop
virtual void stop() override
stop the timer
Definition: timer.cpp:85
mrs_lib::ROSTimer::start
virtual void start() override
start the timer
Definition: timer.cpp:23
mrs_lib::MRSTimer::setPeriod
virtual void setPeriod(const ros::Duration &duration, const bool reset=true)=0
set the timer period/duration
mrs_lib::ROSTimer::running
virtual bool running() override
returns true if callbacks should be called
Definition: timer.cpp:58
mrs_lib::MRSTimer::start
virtual void start()=0
start the timer
mrs_lib::ROSTimer
ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization metho...
Definition: timer.h:77
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::ROSTimer::stop
virtual void stop() override
stop the timer
Definition: timer.cpp:10
mrs_lib::MRSTimer::running
virtual bool running()=0
returns true if callbacks should be called
mrs_lib::ThreadTimer::running
virtual bool running() override
returns true if callbacks should be called
Definition: timer.cpp:117
mrs_lib::MRSTimer::setCallback
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback)=0
change the callback method
mrs_lib::ROSTimer::setPeriod
virtual void setPeriod(const ros::Duration &duration, const bool reset=true) override
set the timer period/duration
Definition: timer.cpp:36
mrs_lib::ROSTimer::setCallback
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback) override
change the callback method
Definition: timer.cpp:49
mrs_lib::ThreadTimer::setPeriod
virtual void setPeriod(const ros::Duration &duration, const bool reset=true) override
set the timer period/duration
Definition: timer.cpp:96
mrs_lib::MRSTimer::stop
virtual void stop()=0
stop the timer
mrs_lib::ThreadTimer::start
virtual void start() override
start the timer
Definition: timer.cpp:74
mrs_lib::MRSTimer
Common wrapper representing the functionality of the ros::Timer.
Definition: timer.h:21
mrs_lib::ThreadTimer
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition: timer.h:167