mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
timer_handler.h
1#ifndef MRS_TIMER_H
2#define MRS_TIMER_H
3
4#include <rclcpp/rclcpp.hpp>
5#include <mutex>
6
7#include <mrs_lib/utils.h>
8
9namespace mrs_lib
10{
11
13 {
14 TimerHandlerOptions(const rclcpp::Node::SharedPtr node) : node(node)
15 {
16 }
17
18 TimerHandlerOptions() = default;
19
20 rclcpp::Node::SharedPtr node;
21
22 bool oneshot = false;
23
24 bool autostart = true;
25
26 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
27 };
28
39 {
40 public:
41 using callback_t = std::function<void()>;
42
46 virtual void stop() = 0;
47
51 virtual void start() = 0;
52
59 virtual void setPeriod(const rclcpp::Duration& duration) = 0;
60
68 virtual void setCallback(const std::function<void()>& callback) = 0;
69
75 virtual bool running() = 0;
76
77 virtual ~MRSTimer() = default;
78 MRSTimer(const MRSTimer&) = default;
79 MRSTimer(MRSTimer&&) = default;
80 MRSTimer& operator=(const MRSTimer&) = default;
81 MRSTimer& operator=(MRSTimer&&) = default;
82
83 protected:
84 MRSTimer() = default;
85
86 rclcpp::Node::SharedPtr node_;
87 };
88
89 // | ------------------------ ROSTimer ------------------------ |
90
91 /* class ROSTimer //{ */
92
96 class ROSTimer : public MRSTimer
97 {
98 public:
99 ROSTimer();
100
101 ROSTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
102
103 ROSTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
104
108 virtual void stop() override;
109
113 virtual void start() override;
114
121 virtual void setPeriod(const rclcpp::Duration& duration) override;
122
130 virtual void setCallback(const std::function<void()>& callback) override;
131
137 virtual bool running() override;
138
139 virtual ~ROSTimer() override
140 {
141 stop();
142 };
143
144 // to keep rule of five since we have a custom destructor
145 ROSTimer(const ROSTimer&) = delete;
146 ROSTimer(ROSTimer&&) = delete;
147 ROSTimer& operator=(const ROSTimer&) = delete;
148 ROSTimer& operator=(ROSTimer&&) = delete;
149
150 private:
151 std::mutex mutex_timer_;
152
153 std::function<void()> callback;
154
155 bool oneshot;
156
157 rclcpp::TimerBase::SharedPtr timer_;
158
159 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
160 };
161
162 //}
163
164 // | ----------------------- ThreadTimer ---------------------- |
165
166 /* class ThreadTimer //{ */
167
171 class ThreadTimer : public MRSTimer
172 {
173
174 public:
175 ThreadTimer();
176
177 ThreadTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
178
179 ThreadTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
180
186 virtual void stop() override;
187
195 virtual void start() override;
196
204 virtual void setPeriod(const rclcpp::Duration& duration) override;
205
213 virtual void setCallback(const std::function<void()>& callback) override;
214
220 virtual bool running() override;
221
227 virtual ~ThreadTimer() override
228 {
229 stop();
230 };
231 // to keep rule of five since we have a custom destructor
232 ThreadTimer(const ThreadTimer&) = delete;
233 ThreadTimer(ThreadTimer&&) = delete;
234 ThreadTimer& operator=(const ThreadTimer&) = delete;
235 ThreadTimer& operator=(ThreadTimer&&) = delete;
236
237 private:
238 class Impl;
239
240 std::unique_ptr<Impl> impl_;
241
242 }; // namespace mrs_lib
243
244 //}
245
246} // namespace mrs_lib
247
248#ifndef MRS_TIMER_HPP
249#include <mrs_lib/impl/timer_handler.hpp>
250#endif
251
252#endif // MRS_TIMER_H
Common wrapper representing the functionality of the rclcpp::Timer.
Definition timer_handler.h:39
virtual void setCallback(const std::function< void()> &callback)=0
change the callback method
virtual bool running()=0
returns true if callbacks should be called
virtual void setPeriod(const rclcpp::Duration &duration)=0
set the timer period/duration
virtual void stop()=0
stop the timer
virtual void start()=0
start the timer
rclcpp::Timer wrapper. The interface is the same as with rclcpp::Timer, except for the initialization...
Definition timer_handler.h:97
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:108
virtual void stop() override
stop the timer
Definition timer_handler.cpp:48
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:84
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:117
virtual void start() override
start the timer
Definition timer_handler.cpp:69
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition timer_handler.h:172
virtual void start() override
start the timer
Definition timer_handler.cpp:159
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition timer_handler.h:227
virtual void stop() override
stop the timer
Definition timer_handler.cpp:172
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:198
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:185
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:211
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition timer_handler.h:13
Defines various general utility functions.