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 TimerHandlerOptions() = default;
18
19 rclcpp::Node::SharedPtr node;
20
21 bool oneshot = false;
22
23 bool autostart = true;
24
25 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
26};
27
37class MRSTimer {
38public:
39 using callback_t = std::function<void()>;
40
44 virtual void stop() = 0;
45
49 virtual void start() = 0;
50
57 virtual void setPeriod(const rclcpp::Duration& duration) = 0;
58
66 virtual void setCallback(const std::function<void()>& callback) = 0;
67
73 virtual bool running() = 0;
74
75 virtual ~MRSTimer() = default;
76 MRSTimer(const MRSTimer&) = default;
77 MRSTimer(MRSTimer&&) = default;
78 MRSTimer& operator=(const MRSTimer&) = default;
79 MRSTimer& operator=(MRSTimer&&) = default;
80
81protected:
82 MRSTimer() = default;
83
84 rclcpp::Node::SharedPtr node_;
85};
86
87// | ------------------------ ROSTimer ------------------------ |
88
89/* class ROSTimer //{ */
90
94class ROSTimer : public MRSTimer {
95public:
96 ROSTimer();
97
98 ROSTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
99
100 ROSTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
101
105 virtual void stop() override;
106
110 virtual void start() override;
111
118 virtual void setPeriod(const rclcpp::Duration& duration) override;
119
127 virtual void setCallback(const std::function<void()>& callback) override;
128
134 virtual bool running() override;
135
136 virtual ~ROSTimer() override {
137 stop();
138 };
139
140 // to keep rule of five since we have a custom destructor
141 ROSTimer(const ROSTimer&) = delete;
142 ROSTimer(ROSTimer&&) = delete;
143 ROSTimer& operator=(const ROSTimer&) = delete;
144 ROSTimer& operator=(ROSTimer&&) = delete;
145
146private:
147 std::mutex mutex_timer_;
148
149 std::function<void()> callback;
150
151 bool oneshot;
152
153 rclcpp::TimerBase::SharedPtr timer_;
154
155 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
156};
157
158//}
159
160// | ----------------------- ThreadTimer ---------------------- |
161
162/* class ThreadTimer //{ */
163
167class ThreadTimer : public MRSTimer {
168
169public:
170 ThreadTimer();
171
172 ThreadTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
173
174 ThreadTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
175
181 virtual void stop() override;
182
190 virtual void start() override;
191
199 virtual void setPeriod(const rclcpp::Duration& duration) override;
200
208 virtual void setCallback(const std::function<void()>& callback) override;
209
215 virtual bool running() override;
216
222 virtual ~ThreadTimer() override {
223 stop();
224 };
225 // to keep rule of five since we have a custom destructor
226 ThreadTimer(const ThreadTimer&) = delete;
227 ThreadTimer(ThreadTimer&&) = delete;
228 ThreadTimer& operator=(const ThreadTimer&) = delete;
229 ThreadTimer& operator=(ThreadTimer&&) = delete;
230
231private:
232 class Impl;
233
234 std::unique_ptr<Impl> impl_;
235
236}; // namespace mrs_lib
237
238//}
239
240} // namespace mrs_lib
241
242#ifndef MRS_TIMER_HPP
243#include <mrs_lib/impl/timer_handler.hpp>
244#endif
245
246#endif // MRS_TIMER_H
Common wrapper representing the functionality of the rclcpp::Timer.
Definition timer_handler.h:37
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:94
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:94
virtual void stop() override
stop the timer
Definition timer_handler.cpp:43
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:74
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:102
virtual void start() override
start the timer
Definition timer_handler.cpp:61
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition timer_handler.h:167
virtual void start() override
start the timer
Definition timer_handler.cpp:138
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition timer_handler.h:222
virtual void stop() override
stop the timer
Definition timer_handler.cpp:149
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:171
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:160
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:182
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.