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

Modifies timers API to select autostart state #2005

Merged
merged 7 commits into from
Jun 21, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
17 changes: 11 additions & 6 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,15 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
{
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
clock,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
node_base->get_context());
node_base->get_context(),
autostart);

node_timers->add_timer(timer, group);
return timer;
Expand All @@ -59,15 +61,17 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
{
return create_timer(
rclcpp::node_interfaces::get_node_base_interface(node),
rclcpp::node_interfaces::get_node_timers_interface(node),
clock,
period,
std::forward<CallbackT>(callback),
group);
group,
autostart);
}

/// Convenience method to create a timer with node resources.
Expand All @@ -92,7 +96,8 @@ create_wall_timer(
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
node_interfaces::NodeTimersInterface * node_timers,
bool autostart = true)
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
{
if (node_base == nullptr) {
throw std::invalid_argument{"input node_base cannot be null"};
Expand Down Expand Up @@ -133,7 +138,7 @@ create_wall_timer(
}

auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period_ns, std::move(callback), node_base->get_context());
period_ns, std::move(callback), node_base->get_context(), autostart);
node_timers->add_timer(timer, group);
return timer;
}
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,13 +232,15 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] period Time interval between triggers of the callback.
* \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.
*/
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);
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true);

/// Create and return a Client.
/**
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 @@ -110,14 +110,16 @@ typename rclcpp::WallTimer<CallbackT>::SharedPtr
Node::create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group)
rclcpp::CallbackGroup::SharedPtr group,
bool autostart)
{
return rclcpp::create_wall_timer(
period,
std::move(callback),
group,
this->node_base_.get(),
this->node_timers_.get());
this->node_timers_.get(),
autostart);
}

template<typename ServiceT>
Expand Down
18 changes: 13 additions & 5 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,14 @@ class TimerBase
* \param clock A clock to use for time and sleeping
* \param period The interval at which the timer fires
* \param context node context
* \param autostart timer state on initialization
*/
RCLCPP_PUBLIC
explicit TimerBase(
Clock::SharedPtr clock,
std::chrono::nanoseconds period,
rclcpp::Context::SharedPtr context);
rclcpp::Context::SharedPtr context,
bool autostart = true);

/// TimerBase destructor
RCLCPP_PUBLIC
Expand Down Expand Up @@ -152,8 +154,11 @@ class TimerBase
protected:
Clock::SharedPtr clock_;
std::shared_ptr<rcl_timer_t> timer_handle_;
rclcpp::Context::SharedPtr context_;
std::chrono::nanoseconds period_;

std::atomic<bool> in_use_by_wait_set_{false};
bool autostart_{false};
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
};


Expand All @@ -179,12 +184,13 @@ 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
*/
explicit GenericTimer(
Clock::SharedPtr clock, std::chrono::nanoseconds period, FunctorT && callback,
rclcpp::Context::SharedPtr context
rclcpp::Context::SharedPtr context, bool autostart = true
)
: TimerBase(clock, period, context), callback_(std::forward<FunctorT>(callback))
: TimerBase(clock, period, context, autostart), callback_(std::forward<FunctorT>(callback))
{
TRACEPOINT(
rclcpp_timer_callback_added,
Expand Down Expand Up @@ -287,13 +293,15 @@ class WallTimer : public GenericTimer<FunctorT>
* \param period The interval at which the timer fires
* \param callback The callback function to execute every interval
* \param context node context
* \param autostart timer state on initialization
*/
WallTimer(
std::chrono::nanoseconds period,
FunctorT && callback,
rclcpp::Context::SharedPtr context)
rclcpp::Context::SharedPtr context,
bool autostart = true)
: GenericTimer<FunctorT>(
std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback), context)
std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback), context, autostart)
{}

protected:
Expand Down
9 changes: 5 additions & 4 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,9 @@ using rclcpp::TimerBase;
TimerBase::TimerBase(
rclcpp::Clock::SharedPtr clock,
std::chrono::nanoseconds period,
rclcpp::Context::SharedPtr context)
: clock_(clock), timer_handle_(nullptr)
rclcpp::Context::SharedPtr context,
bool autostart)
: clock_(clock), timer_handle_(nullptr), context_(context), period_(period), autostart_(autostart)
{
if (nullptr == context) {
context = rclcpp::contexts::get_global_default_context();
Expand Down Expand Up @@ -62,8 +63,8 @@ TimerBase::TimerBase(
{
std::lock_guard<std::mutex> clock_guard(clock_->get_clock_mutex());
rcl_ret_t ret = rcl_timer_init(
timer_handle_.get(), clock_handle, rcl_context.get(), period.count(), nullptr,
rcl_get_default_allocator());
timer_handle_.get(), clock_handle, rcl_context.get(), period.count(),
nullptr, rcl_get_default_allocator(), autostart_);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't initialize rcl timer handle");
}
Expand Down
25 changes: 25 additions & 0 deletions rclcpp/test/rclcpp/test_create_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,3 +133,28 @@ TEST(TestCreateTimer, timer_function_pointer)

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,
node->get_clock(),
rclcpp::Duration(0ms),
[]() {},
nullptr,
false);

ASSERT_TRUE(timer->is_canceled());

timer->reset();
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved

ASSERT_FALSE(timer->is_canceled());

timer->cancel();

rclcpp::shutdown();
}
24 changes: 24 additions & 0 deletions rclcpp/test/rclcpp/test_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,20 @@ class TestTimer : public ::testing::Test
);
EXPECT_TRUE(timer->is_steady());

timer_without_autostart = test_node->create_wall_timer(
100ms,
[this]() -> void
{
this->has_timer_run.store(true);

if (this->cancel_timer.load()) {
this->timer->cancel();
}
// prevent any tests running timer from blocking
this->executor->cancel();
}, nullptr, false);
EXPECT_TRUE(timer_without_autostart->is_steady());

executor->add_node(test_node);
// don't start spinning, let the test dictate when
}
Expand All @@ -78,6 +92,7 @@ class TestTimer : public ::testing::Test
std::atomic<bool> cancel_timer;
rclcpp::Node::SharedPtr test_node;
std::shared_ptr<rclcpp::TimerBase> timer;
std::shared_ptr<rclcpp::TimerBase> timer_without_autostart;
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor;
};

Expand Down Expand Up @@ -283,3 +298,12 @@ TEST_F(TestTimer, test_failures_with_exceptions)
std::runtime_error("Timer could not get time until next call: error not set"));
}
}

/// Simple test of a timer without autostart
TEST_F(TestTimer, test_timer_without_autostart)
{
EXPECT_TRUE(timer_without_autostart->is_canceled());
// Reset to change start timer
timer_without_autostart->reset();
EXPECT_FALSE(timer_without_autostart->is_canceled());
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
}