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) {
15 this->timer_ = std::make_unique<ros::Timer>(nh.createTimer(duration, callback, obj, 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) {
23 this->timer_ = std::make_unique<ros::Timer>(nh.createTimer(rate, callback, obj, oneshot, autostart));
34 Impl(
const std::function<
void(
const ros::TimerEvent&)>& callback,
const ros::Duration& delay_dur,
const bool oneshot);
39 void setPeriod(
const ros::Duration& duration,
const bool reset =
true);
40 void setCallback(
const std::function<
void(
const ros::TimerEvent&)>& callback);
42 friend class ThreadTimer;
47 Impl& operator=(
const Impl&) =
delete;
52 std::function<void(
const ros::TimerEvent&)> callback_;
56 bool breakableSleep(
const ros::Time& until);
59 std::mutex mutex_wakeup_;
60 std::condition_variable wakeup_cond_;
61 std::recursive_mutex mutex_state_;
63 ros::Duration delay_dur_;
65 ros::Time next_expected_;
66 ros::Time last_expected_;
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)
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)
86 const auto cbk = std::bind(callback, obj, std::placeholders::_1);
87 if (duration == ros::Duration(0))
89 this->impl_ = std::make_unique<Impl>(cbk, duration, oneshot);
96 #endif // MRS_TIMER_HPP