Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Timer that can be triggered a finite number of times. #2006

Open
wants to merge 17 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 19 additions & 8 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,8 @@ create_timer(
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
bool autostart = true,
uint32_t number_of_callbacks = 0)
{
return create_timer(
clock,
Expand All @@ -100,7 +101,8 @@ create_timer(
group,
node_base.get(),
node_timers.get(),
autostart);
autostart,
number_of_callbacks);
}

/// Create a timer with a given clock
Expand All @@ -112,7 +114,8 @@ create_timer(
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
bool autostart = true,
uint32_t number_of_callbacks = 0)
{
return create_timer(
clock,
Expand All @@ -121,7 +124,8 @@ create_timer(
group,
rclcpp::node_interfaces::get_node_base_interface(node).get(),
rclcpp::node_interfaces::get_node_timers_interface(node).get(),
autostart);
autostart,
number_of_callbacks);
}

/// Convenience method to create a general timer with node resources.
Expand All @@ -137,6 +141,10 @@ create_timer(
* \param node_base node base interface
* \param node_timers node timer interface
* \param autostart defines if the timer should start it's countdown on initialization or not.
* \param number_of_callbacks Number of times the callback will be triggered.
* If the value is 0 (the default), the callback will be called
* continuously until it is canceled.
* that means an infinite amount of callbacks i.e. the clock's default behavior.
* \return shared pointer to a generic timer
* \throws std::invalid_argument if either clock, node_base or node_timers
* are nullptr, or period is negative or too large
Expand All @@ -150,7 +158,8 @@ create_timer(
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers,
bool autostart = true)
bool autostart = true,
uint32_t number_of_callbacks = 0)
{
if (clock == nullptr) {
throw std::invalid_argument{"clock cannot be null"};
Expand All @@ -166,7 +175,8 @@ create_timer(

// Add a new generic timer.
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
std::move(clock), period_ns, std::move(callback), node_base->get_context(), autostart);
std::move(clock), period_ns, std::move(callback), node_base->get_context(), autostart,
number_of_callbacks);
node_timers->add_timer(timer, group);
return timer;
}
Expand Down Expand Up @@ -194,7 +204,8 @@ create_wall_timer(
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers,
bool autostart = true)
bool autostart = true,
uint32_t number_of_callbacks = 0)
{
if (node_base == nullptr) {
throw std::invalid_argument{"input node_base cannot be null"};
Expand All @@ -208,7 +219,7 @@ create_wall_timer(

// Add a new wall timer.
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period_ns, std::move(callback), node_base->get_context(), autostart);
period_ns, std::move(callback), node_base->get_context(), autostart, number_of_callbacks);
node_timers->add_timer(timer, group);
return timer;
}
Expand Down
6 changes: 5 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,14 +234,18 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] callback User-defined callback function.
* \param[in] group Callback group to execute this timer's callback in.
* \param[in] autostart The state of the clock on initialization.
* \param[in] number_of_callbacks Number of times the callback will be triggered.
* If the value is 0 (the default), the callback will be called
* continuously until it is canceled.
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true);
bool autostart = true,
uint32_t number_of_callbacks = 0);

/// Create a timer that uses the node clock to drive the callback.
/**
Expand Down
6 changes: 4 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,15 +111,17 @@ Node::create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
bool autostart)
bool autostart,
uint32_t number_of_callbacks)
{
return rclcpp::create_wall_timer(
period,
std::move(callback),
group,
this->node_base_.get(),
this->node_timers_.get(),
autostart);
autostart,
number_of_callbacks);
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
Expand Down
36 changes: 30 additions & 6 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ class TimerBase

Clock::SharedPtr clock_;
std::shared_ptr<rcl_timer_t> timer_handle_;
uint32_t callbacks_called_;

std::atomic<bool> in_use_by_wait_set_{false};

Expand All @@ -202,7 +203,10 @@ class TimerBase
using VoidCallbackType = std::function<void ()>;
using TimerCallbackType = std::function<void (TimerBase &)>;

/// Generic timer. Periodically executes a user-specified callback.
/// Generic timer. Periodically executes a user-specified callback. The user
/// can specify a finite amount of times that the callback will be executed
/// and the timer will cancel itself after that. Otherwise, it will keep exe-
/// cuting the callback on each period.
Comment on lines +208 to +209
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
/// and the timer will cancel itself after that. Otherwise, it will keep exe-
/// cuting the callback on each period.
/// and the timer will cancel itself after that. Otherwise, it will keep
/// executing the callback on each period.

template<
typename FunctorT,
typename std::enable_if<
Expand All @@ -221,14 +225,20 @@ class GenericTimer : public TimerBase
* \param[in] period The interval at which the timer fires.
* \param[in] callback User-specified callback function.
* \param[in] context custom context to be used.
* \param autostart timer state on initialization
* \param[in] autostart timer state on initialization
* \param[in] number_of_callbacks Number of times the callback will be triggered.
* If the value is 0 (the default), the callback will be called
* continuously until it is canceled.
*/
explicit GenericTimer(
Clock::SharedPtr clock, std::chrono::nanoseconds period, FunctorT && callback,
rclcpp::Context::SharedPtr context, bool autostart = true
rclcpp::Context::SharedPtr context, bool autostart = true,
uint32_t number_of_callbacks = 0
)
: TimerBase(clock, period, context, autostart), callback_(std::forward<FunctorT>(callback))
: TimerBase(clock, period, context, autostart), callback_(std::forward<FunctorT>(callback)),
number_of_callbacks_(number_of_callbacks)
{
callbacks_called_ = 0;
TRACETOOLS_TRACEPOINT(
rclcpp_timer_callback_added,
static_cast<const void *>(get_timer_handle().get()),
Expand Down Expand Up @@ -271,13 +281,23 @@ class GenericTimer : public TimerBase

/**
* \sa rclcpp::TimerBase::execute_callback
* This method will call the callback function and execute it. After executing
* the callback it will check if the timer was created with a finite amount of
* times it will be triggered and cancel itself after executing the callback that
* amount of times. If there was no finite amount of callbacks to call, the timer
* will always be triggered on each period.
*/
void
execute_callback() override
{
TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
execute_callback_delegate<>();
TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
if (number_of_callbacks_ != 0) {
if (number_of_callbacks_ <= ++callbacks_called_) {
cancel();
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
}
}
}

// void specialization
Expand Down Expand Up @@ -317,6 +337,7 @@ class GenericTimer : public TimerBase
RCLCPP_DISABLE_COPY(GenericTimer)

FunctorT callback_;
uint32_t number_of_callbacks_;
};

template<
Expand All @@ -337,14 +358,17 @@ class WallTimer : public GenericTimer<FunctorT>
* \param callback The callback function to execute every interval
* \param context node context
* \param autostart timer state on initialization
* \param number_of_callbacks Quantity of times the callback will be triggered.
*/
WallTimer(
std::chrono::nanoseconds period,
FunctorT && callback,
rclcpp::Context::SharedPtr context,
bool autostart = true)
bool autostart = true,
uint32_t number_of_callbacks = 0)
: GenericTimer<FunctorT>(
std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback), context, autostart)
std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback), context, autostart,
number_of_callbacks)
{}

protected:
Expand Down
1 change: 1 addition & 0 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ TimerBase::reset()
std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
ret = rcl_timer_reset(timer_handle_.get());
}
callbacks_called_ = 0;
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't reset timer");
}
Expand Down
42 changes: 41 additions & 1 deletion rclcpp/test/rclcpp/test_create_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,11 +194,51 @@ TEST(TestCreateTimer, timer_function_pointer)
rclcpp::shutdown();
}

TEST(TestCreateTimer, timer_triggered_twice)
{
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("test_timer_triggered_twice");

std::atomic<int> callback_counter{0};

rclcpp::TimerBase::SharedPtr timer;
timer = rclcpp::create_timer(
node,
node->get_clock(),
rclcpp::Duration(0ms),
[&callback_counter]() {
callback_counter += 1;
}, nullptr, true, 2);

rclcpp::spin_some(node);
ASSERT_EQ(1, callback_counter);

rclcpp::spin_some(node);
ASSERT_EQ(2, callback_counter);

rclcpp::spin_some(node);
ASSERT_EQ(2, callback_counter);
ASSERT_TRUE(timer->is_canceled());

timer->reset();

rclcpp::spin_some(node);
ASSERT_EQ(3, callback_counter);

rclcpp::spin_some(node);
ASSERT_EQ(4, callback_counter);

rclcpp::spin_some(node);
ASSERT_EQ(4, callback_counter);
ASSERT_TRUE(timer->is_canceled());
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved

rclcpp::shutdown();
}

TEST(TestCreateTimer, timer_without_autostart)
{
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("test_create_timer_node");

rclcpp::TimerBase::SharedPtr timer;
timer = rclcpp::create_timer(
node,
Expand Down
27 changes: 27 additions & 0 deletions rclcpp/test/rclcpp/test_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,6 +350,33 @@ INSTANTIATE_TEST_SUITE_P(
}
);

TEST_P(TestTimer, test_timer_triggered_once) {
std::atomic<int> callback_counter{0};

rclcpp::TimerBase::SharedPtr timer_called_twice;
timer_called_twice = test_node->create_wall_timer(
0ms,
[&callback_counter]() {
callback_counter += 1;
}, nullptr, true, 1);

executor->spin();
ASSERT_EQ(1, callback_counter);

executor->spin();
ASSERT_EQ(1, callback_counter);
ASSERT_TRUE(timer_called_twice->is_canceled());

timer_called_twice->reset();

executor->spin();
ASSERT_EQ(2, callback_counter);

executor->spin();
ASSERT_EQ(2, callback_counter);
ASSERT_TRUE(timer_called_twice->is_canceled());
}

/// Simple test of a timer without autostart
TEST_P(TestTimer, test_timer_without_autostart)
{
Expand Down