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

Add a create_timer method to Node and LifecycleNode classes #1975

Merged
Merged
Show file tree
Hide file tree
Changes from 23 commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
efc08b7
Add a create_timer method to the Node class
asymingt Jul 22, 2022
3b359ad
Updated unit tests to check both wall timers and generic timers
asymingt Jul 22, 2022
45e6886
Added a create_timer test for the newly-added function.
asymingt Aug 1, 2022
9fd618f
Try modifying the sim test to increment with rclcpp::Duration() to av…
asymingt Aug 1, 2022
e07fdd9
Update lifecycle node to also support create_timer
asymingt Aug 1, 2022
ac4af54
Uncrustify one file.
asymingt Aug 2, 2022
8e23724
Fix a test to use a create_timer when use_sim_time:=True
asymingt Aug 2, 2022
c587718
Fixed the timer tests that were calling create_wall_timer in TEST_P i…
asymingt Aug 2, 2022
e3fffe2
CI nondeterminism test #1
asymingt Aug 2, 2022
2c7fe5c
CI nondeterminism test #2
asymingt Aug 2, 2022
879a512
CI nondeterminism test #3
asymingt Aug 2, 2022
7a21ff3
CI nondeterminism test #4
asymingt Aug 2, 2022
59d32c3
CI nondeterminism test #5
asymingt Aug 2, 2022
3f16cb2
Rename lambda function and update timeout duration.
asymingt Aug 17, 2022
7d77162
Move from 10s -> 2s max check duration in test_time_source
asymingt Aug 17, 2022
af24d74
Refactor create_timer to use shared_ptr and follow a predictable call…
asymingt Aug 17, 2022
b8338e8
Include a missing header file
asymingt Aug 18, 2022
95afb7e
Correct a time comparison in spin_until_time
asymingt Aug 19, 2022
f05c81c
Revert "Refactor create_timer to use shared_ptr and follow a predicta…
ivanpauno Aug 25, 2022
a5c956c
Adjust create_timer() overloads, reuse code
ivanpauno Aug 26, 2022
2e6e4ff
Comment out problematic test
ivanpauno Aug 26, 2022
1c16100
Please linters
ivanpauno Aug 26, 2022
2a9e6f6
Fix rclcpp_lifecycle
ivanpauno Aug 26, 2022
7e24c8d
nit
ivanpauno Aug 29, 2022
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
155 changes: 111 additions & 44 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,63 @@

#include "rclcpp/duration.hpp"
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
#include "rclcpp/node_interfaces/get_node_clock_interface.hpp"
#include "rclcpp/node_interfaces/get_node_timers_interface.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/node_interfaces/node_timers_interface.hpp"

namespace rclcpp
{
namespace detail
{
/// Perform a safe cast to a timer period in nanoseconds
/**
*
* \tparam DurationRepT
* \tparam DurationT
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
* \return period, expressed as chrono::duration::nanoseconds
* \throws std::invalid_argument if period is negative or too large
*/
template<typename DurationRepT, typename DurationT>
std::chrono::nanoseconds
safe_cast_to_period_in_ns(std::chrono::duration<DurationRepT, DurationT> period)
{
if (period < std::chrono::duration<DurationRepT, DurationT>::zero()) {
throw std::invalid_argument{"timer period cannot be negative"};
}

// Casting to a double representation might lose precision and allow the check below to succeed
// but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max.
constexpr auto maximum_safe_cast_ns =
std::chrono::nanoseconds::max() - std::chrono::duration<DurationRepT, DurationT>(1);

// If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow
// a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is
// greater than nanoseconds::max() is a difficult general problem. This is a more conservative
// version of Howard Hinnant's (the <chrono> guy>) response here:
// https://stackoverflow.com/a/44637334/2089061
// However, this doesn't solve the issue for all possible duration types of period.
// Follow-up issue: https://github.com/ros2/rclcpp/issues/1177
constexpr auto ns_max_as_double =
std::chrono::duration_cast<std::chrono::duration<double, std::chrono::nanoseconds::period>>(
maximum_safe_cast_ns);
if (period > ns_max_as_double) {
throw std::invalid_argument{
"timer period must be less than std::chrono::nanoseconds::max()"};
}

const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(period);
if (period_ns < std::chrono::nanoseconds::zero()) {
throw std::runtime_error{
"Casting timer period to nanoseconds resulted in integer overflow."};
}

return period_ns;
}
} // namespace detail

/// Create a timer with a given clock
/// \internal
template<typename CallbackT>
Expand All @@ -41,14 +92,13 @@ create_timer(
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
{
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
return create_timer(
node_base.get(),
node_timers.get(),
clock,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
node_base->get_context());

node_timers->add_timer(timer, group);
return timer;
group);
}

/// Create a timer with a given clock
Expand All @@ -62,82 +112,99 @@ create_timer(
rclcpp::CallbackGroup::SharedPtr group = nullptr)
{
return create_timer(
rclcpp::node_interfaces::get_node_base_interface(node),
rclcpp::node_interfaces::get_node_timers_interface(node),
clock,
period,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
group);
group,
rclcpp::node_interfaces::get_node_base_interface(node).get(),
rclcpp::node_interfaces::get_node_timers_interface(node).get());
}

/// Convenience method to create a timer with node resources.
/// Convenience method to create a general timer with node resources.
/**
*
* \tparam DurationRepT
* \tparam DurationT
* \tparam CallbackT
* \param clock clock to be used
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
* \param callback callback to execute via the timer period
* \param group
* \param node_base
* \param node_timers
* \return
* \throws std::invalid argument if either node_base or node_timers
* are null, or period is negative or too large
* \param group callback group
* \param node_base node base interface
* \param node_timers node timer interface
* \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
*/
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
rclcpp::Clock::SharedPtr clock,
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
{
if (clock == nullptr) {
throw std::invalid_argument{"clock cannot be null"};
}
if (node_base == nullptr) {
throw std::invalid_argument{"input node_base cannot be null"};
}

if (node_timers == nullptr) {
throw std::invalid_argument{"input node_timers cannot be null"};
}

if (period < std::chrono::duration<DurationRepT, DurationT>::zero()) {
throw std::invalid_argument{"timer period cannot be negative"};
}
const std::chrono::nanoseconds period_ns = detail::safe_cast_to_period_in_ns(period);

// Casting to a double representation might lose precision and allow the check below to succeed
// but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max.
constexpr auto maximum_safe_cast_ns =
std::chrono::nanoseconds::max() - std::chrono::duration<DurationRepT, DurationT>(1);
// Add a new generic timer.
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
std::move(clock), period_ns, std::move(callback), node_base->get_context());
node_timers->add_timer(timer, group);
return timer;
}

// If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow
// a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is
// greater than nanoseconds::max() is a difficult general problem. This is a more conservative
// version of Howard Hinnant's (the <chrono> guy>) response here:
// https://stackoverflow.com/a/44637334/2089061
// However, this doesn't solve the issue for all possible duration types of period.
// Follow-up issue: https://github.com/ros2/rclcpp/issues/1177
constexpr auto ns_max_as_double =
std::chrono::duration_cast<std::chrono::duration<double, std::chrono::nanoseconds::period>>(
maximum_safe_cast_ns);
if (period > ns_max_as_double) {
throw std::invalid_argument{
"timer period must be less than std::chrono::nanoseconds::max()"};
/// Convenience method to create a wall timer with node resources.
/**
*
* \tparam DurationRepT
* \tparam DurationT
* \tparam CallbackT
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
* \param callback callback to execute via the timer period
* \param group callback group
* \param node_base node base interface
* \param node_timers node timer interface
* \return shared pointer to a wall timer
* \throws std::invalid_argument if either node_base or node_timers
* are null, or period is negative or too large
*/
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
{
if (node_base == nullptr) {
throw std::invalid_argument{"input node_base cannot be null"};
}

const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(period);
if (period_ns < std::chrono::nanoseconds::zero()) {
throw std::runtime_error{
"Casting timer period to nanoseconds resulted in integer overflow."};
if (node_timers == nullptr) {
throw std::invalid_argument{"input node_timers cannot be null"};
}

const std::chrono::nanoseconds period_ns = detail::safe_cast_to_period_in_ns(period);

// Add a new wall timer.
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period_ns, std::move(callback), node_base->get_context());
node_timers->add_timer(timer, group);
return timer;
}

} // namespace rclcpp

#endif // RCLCPP__CREATE_TIMER_HPP_
15 changes: 14 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ class Node : public std::enable_shared_from_this<Node>
)
);

/// Create a timer.
/// Create a wall timer that uses the wall clock to drive the callback.
/**
* \param[in] period Time interval between triggers of the callback.
* \param[in] callback User-defined callback function.
Expand All @@ -240,6 +240,19 @@ class Node : public std::enable_shared_from_this<Node>
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/// Create a timer that uses the node clock to drive the callback.
/**
* \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.
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/// Create and return a Client.
/**
* \param[in] service_name The topic to service on.
Expand Down
16 changes: 16 additions & 0 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,22 @@ Node::create_wall_timer(
this->node_timers_.get());
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
Node::create_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_timer(
this->get_clock(),
period,
std::move(callback),
group,
this->node_base_.get(),
this->node_timers_.get());
}

template<typename ServiceT>
typename Client<ServiceT>::SharedPtr
Node::create_client(
Expand Down
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_topics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__NODE_INTERFACES__NODE_TOPICS_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_TOPICS_HPP_

#include <memory>
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
#include <string>

#include "rcl/publisher.h"
Expand Down
62 changes: 61 additions & 1 deletion rclcpp/test/rclcpp/test_create_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ TEST(TestCreateTimer, call_with_node_wrapper_compiles)
rclcpp::shutdown();
}

TEST(TestCreateTimer, call_wall_timer_with_bad_arguments)
TEST(TestCreateWallTimer, call_wall_timer_with_bad_arguments)
{
rclcpp::init(0, nullptr);
NodeWrapper node("test_create_wall_timers_with_bad_arguments");
Expand Down Expand Up @@ -117,6 +117,66 @@ TEST(TestCreateTimer, call_wall_timer_with_bad_arguments)
rclcpp::shutdown();
}

TEST(TestCreateTimer, call_timer_with_bad_arguments)
{
rclcpp::init(0, nullptr);
NodeWrapper node("test_create_timers_with_bad_arguments");
auto callback = []() {};
rclcpp::CallbackGroup::SharedPtr group = nullptr;
auto node_interface =
rclcpp::node_interfaces::get_node_base_interface(node).get();
auto timers_interface =
rclcpp::node_interfaces::get_node_timers_interface(node).get();

auto clock = node.get_node_clock_interface()->get_clock();

// Negative period
EXPECT_THROW(
rclcpp::create_timer(
clock, -1ms, callback, group, node_interface, timers_interface),
std::invalid_argument);

// Very negative period
constexpr auto nanoseconds_min = std::chrono::nanoseconds::min();
EXPECT_THROW(
rclcpp::create_timer(
clock, nanoseconds_min, callback, group, node_interface, timers_interface),
std::invalid_argument);

// Period must be less than nanoseconds::max()
constexpr auto nanoseconds_max = std::chrono::nanoseconds::min();
EXPECT_THROW(
rclcpp::create_timer(
clock, nanoseconds_max, callback, group, node_interface, timers_interface),
std::invalid_argument);

EXPECT_NO_THROW(
rclcpp::create_timer(
clock, nanoseconds_max - 1us, callback, group, node_interface, timers_interface));

EXPECT_NO_THROW(
rclcpp::create_timer(clock, 0ms, callback, group, node_interface, timers_interface));

// Period must be less than nanoseconds::max()
constexpr auto hours_max = std::chrono::hours::max();
EXPECT_THROW(
rclcpp::create_timer(
clock, hours_max, callback, group, node_interface, timers_interface),
std::invalid_argument);

// node_interface is null
EXPECT_THROW(
rclcpp::create_timer(clock, 1ms, callback, group, nullptr, timers_interface),
std::invalid_argument);

// timers_interface is null
EXPECT_THROW(
rclcpp::create_timer(clock, 1ms, callback, group, node_interface, nullptr),
std::invalid_argument);

rclcpp::shutdown();
}

static void test_timer_callback(void) {}

TEST(TestCreateTimer, timer_function_pointer)
Expand Down
Loading