|
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
7 #include <condition_variable>
24 using callback_t = std::function<void(
const ros::TimerEvent&)>;
29 virtual void stop() = 0;
34 virtual void start() = 0;
42 virtual void setPeriod(
const ros::Duration& duration,
const bool reset =
true) = 0;
51 virtual void setCallback(
const std::function<
void(
const ros::TimerEvent&)>& callback) = 0;
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);
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);
114 virtual void stop()
override;
119 virtual void start()
override;
127 virtual void setPeriod(
const ros::Duration& duration,
const bool reset =
true)
override;
136 virtual void setCallback(
const std::function<
void(
const ros::TimerEvent&)>& callback)
override;
143 virtual bool running()
override;
153 std::mutex mutex_timer_;
155 std::unique_ptr<ros::Timer> timer_;
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);
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);
207 virtual void stop()
override;
216 virtual void start()
override;
226 virtual void setPeriod(
const ros::Duration& duration,
const bool reset =
true)
override;
235 virtual void setCallback(
const std::function<
void(
const ros::TimerEvent&)>& callback)
override;
242 virtual bool running()
override;
259 std::unique_ptr<Impl> impl_;
265 #include <mrs_lib/impl/timer.hpp>
269 #endif // MRS_TIMER_H
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition: timer.h:249
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback) override
change the callback method
Definition: timer.cpp:107
virtual void stop() override
stop the timer
Definition: timer.cpp:85
virtual void start() override
start the timer
Definition: timer.cpp:23
virtual void setPeriod(const ros::Duration &duration, const bool reset=true)=0
set the timer period/duration
virtual bool running() override
returns true if callbacks should be called
Definition: timer.cpp:58
virtual void start()=0
start the timer
ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization metho...
Definition: timer.h:77
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
virtual void stop() override
stop the timer
Definition: timer.cpp:10
virtual bool running()=0
returns true if callbacks should be called
virtual bool running() override
returns true if callbacks should be called
Definition: timer.cpp:117
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback)=0
change the callback method
virtual void setPeriod(const ros::Duration &duration, const bool reset=true) override
set the timer period/duration
Definition: timer.cpp:36
virtual void setCallback(const std::function< void(const ros::TimerEvent &)> &callback) override
change the callback method
Definition: timer.cpp:49
virtual void setPeriod(const ros::Duration &duration, const bool reset=true) override
set the timer period/duration
Definition: timer.cpp:96
virtual void stop()=0
stop the timer
virtual void start() override
start the timer
Definition: timer.cpp:74
Common wrapper representing the functionality of the ros::Timer.
Definition: timer.h:21
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition: timer.h:167