Skip to content

Commit 11b5f8d

Browse files
authored
Revert "Add a create_timer method to Node and LifecycleNode classes (#1975)" (#2009)
This reverts commit 6167a57. Signed-off-by: Shane Loretz <sloretz@openrobotics.org> Signed-off-by: Shane Loretz <sloretz@openrobotics.org>
1 parent 6167a57 commit 11b5f8d

9 files changed

Lines changed: 119 additions & 394 deletions

File tree

rclcpp/include/rclcpp/create_timer.hpp

Lines changed: 44 additions & 111 deletions
Original file line numberDiff line numberDiff line change
@@ -23,63 +23,12 @@
2323

2424
#include "rclcpp/duration.hpp"
2525
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
26-
#include "rclcpp/node_interfaces/get_node_clock_interface.hpp"
2726
#include "rclcpp/node_interfaces/get_node_timers_interface.hpp"
2827
#include "rclcpp/node_interfaces/node_base_interface.hpp"
29-
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
3028
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
3129

3230
namespace rclcpp
3331
{
34-
namespace detail
35-
{
36-
/// Perform a safe cast to a timer period in nanoseconds
37-
/**
38-
*
39-
* \tparam DurationRepT
40-
* \tparam DurationT
41-
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
42-
* \return period, expressed as chrono::duration::nanoseconds
43-
* \throws std::invalid_argument if period is negative or too large
44-
*/
45-
template<typename DurationRepT, typename DurationT>
46-
std::chrono::nanoseconds
47-
safe_cast_to_period_in_ns(std::chrono::duration<DurationRepT, DurationT> period)
48-
{
49-
if (period < std::chrono::duration<DurationRepT, DurationT>::zero()) {
50-
throw std::invalid_argument{"timer period cannot be negative"};
51-
}
52-
53-
// Casting to a double representation might lose precision and allow the check below to succeed
54-
// but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max.
55-
constexpr auto maximum_safe_cast_ns =
56-
std::chrono::nanoseconds::max() - std::chrono::duration<DurationRepT, DurationT>(1);
57-
58-
// If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow
59-
// a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is
60-
// greater than nanoseconds::max() is a difficult general problem. This is a more conservative
61-
// version of Howard Hinnant's (the <chrono> guy>) response here:
62-
// https://stackoverflow.com/a/44637334/2089061
63-
// However, this doesn't solve the issue for all possible duration types of period.
64-
// Follow-up issue: https://github.com/ros2/rclcpp/issues/1177
65-
constexpr auto ns_max_as_double =
66-
std::chrono::duration_cast<std::chrono::duration<double, std::chrono::nanoseconds::period>>(
67-
maximum_safe_cast_ns);
68-
if (period > ns_max_as_double) {
69-
throw std::invalid_argument{
70-
"timer period must be less than std::chrono::nanoseconds::max()"};
71-
}
72-
73-
const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(period);
74-
if (period_ns < std::chrono::nanoseconds::zero()) {
75-
throw std::runtime_error{
76-
"Casting timer period to nanoseconds resulted in integer overflow."};
77-
}
78-
79-
return period_ns;
80-
}
81-
} // namespace detail
82-
8332
/// Create a timer with a given clock
8433
/// \internal
8534
template<typename CallbackT>
@@ -92,13 +41,14 @@ create_timer(
9241
CallbackT && callback,
9342
rclcpp::CallbackGroup::SharedPtr group = nullptr)
9443
{
95-
return create_timer(
96-
node_base.get(),
97-
node_timers.get(),
44+
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
9845
clock,
9946
period.to_chrono<std::chrono::nanoseconds>(),
10047
std::forward<CallbackT>(callback),
101-
group);
48+
node_base->get_context());
49+
50+
node_timers->add_timer(timer, group);
51+
return timer;
10252
}
10353

10454
/// Create a timer with a given clock
@@ -112,99 +62,82 @@ create_timer(
11262
rclcpp::CallbackGroup::SharedPtr group = nullptr)
11363
{
11464
return create_timer(
65+
rclcpp::node_interfaces::get_node_base_interface(node),
66+
rclcpp::node_interfaces::get_node_timers_interface(node),
11567
clock,
116-
period.to_chrono<std::chrono::nanoseconds>(),
68+
period,
11769
std::forward<CallbackT>(callback),
118-
group,
119-
rclcpp::node_interfaces::get_node_base_interface(node).get(),
120-
rclcpp::node_interfaces::get_node_timers_interface(node).get());
70+
group);
12171
}
12272

123-
/// Convenience method to create a general timer with node resources.
73+
/// Convenience method to create a timer with node resources.
12474
/**
12575
*
12676
* \tparam DurationRepT
12777
* \tparam DurationT
12878
* \tparam CallbackT
129-
* \param clock clock to be used
13079
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
13180
* \param callback callback to execute via the timer period
132-
* \param group callback group
133-
* \param node_base node base interface
134-
* \param node_timers node timer interface
135-
* \return shared pointer to a generic timer
136-
* \throws std::invalid_argument if either clock, node_base or node_timers
137-
* are nullptr, or period is negative or too large
81+
* \param group
82+
* \param node_base
83+
* \param node_timers
84+
* \return
85+
* \throws std::invalid argument if either node_base or node_timers
86+
* are null, or period is negative or too large
13887
*/
13988
template<typename DurationRepT, typename DurationT, typename CallbackT>
140-
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
141-
create_timer(
142-
rclcpp::Clock::SharedPtr clock,
89+
typename rclcpp::WallTimer<CallbackT>::SharedPtr
90+
create_wall_timer(
14391
std::chrono::duration<DurationRepT, DurationT> period,
14492
CallbackT callback,
14593
rclcpp::CallbackGroup::SharedPtr group,
14694
node_interfaces::NodeBaseInterface * node_base,
14795
node_interfaces::NodeTimersInterface * node_timers)
14896
{
149-
if (clock == nullptr) {
150-
throw std::invalid_argument{"clock cannot be null"};
151-
}
15297
if (node_base == nullptr) {
15398
throw std::invalid_argument{"input node_base cannot be null"};
15499
}
100+
155101
if (node_timers == nullptr) {
156102
throw std::invalid_argument{"input node_timers cannot be null"};
157103
}
158104

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

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

168-
/// Convenience method to create a wall timer with node resources.
169-
/**
170-
*
171-
* \tparam DurationRepT
172-
* \tparam DurationT
173-
* \tparam CallbackT
174-
* \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max()
175-
* \param callback callback to execute via the timer period
176-
* \param group callback group
177-
* \param node_base node base interface
178-
* \param node_timers node timer interface
179-
* \return shared pointer to a wall timer
180-
* \throws std::invalid_argument if either node_base or node_timers
181-
* are null, or period is negative or too large
182-
*/
183-
template<typename DurationRepT, typename DurationT, typename CallbackT>
184-
typename rclcpp::WallTimer<CallbackT>::SharedPtr
185-
create_wall_timer(
186-
std::chrono::duration<DurationRepT, DurationT> period,
187-
CallbackT callback,
188-
rclcpp::CallbackGroup::SharedPtr group,
189-
node_interfaces::NodeBaseInterface * node_base,
190-
node_interfaces::NodeTimersInterface * node_timers)
191-
{
192-
if (node_base == nullptr) {
193-
throw std::invalid_argument{"input node_base cannot be null"};
114+
// If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow
115+
// a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is
116+
// greater than nanoseconds::max() is a difficult general problem. This is a more conservative
117+
// version of Howard Hinnant's (the <chrono> guy>) response here:
118+
// https://stackoverflow.com/a/44637334/2089061
119+
// However, this doesn't solve the issue for all possible duration types of period.
120+
// Follow-up issue: https://github.com/ros2/rclcpp/issues/1177
121+
constexpr auto ns_max_as_double =
122+
std::chrono::duration_cast<std::chrono::duration<double, std::chrono::nanoseconds::period>>(
123+
maximum_safe_cast_ns);
124+
if (period > ns_max_as_double) {
125+
throw std::invalid_argument{
126+
"timer period must be less than std::chrono::nanoseconds::max()"};
194127
}
195128

196-
if (node_timers == nullptr) {
197-
throw std::invalid_argument{"input node_timers cannot be null"};
129+
const auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(period);
130+
if (period_ns < std::chrono::nanoseconds::zero()) {
131+
throw std::runtime_error{
132+
"Casting timer period to nanoseconds resulted in integer overflow."};
198133
}
199134

200-
const std::chrono::nanoseconds period_ns = detail::safe_cast_to_period_in_ns(period);
201-
202-
// Add a new wall timer.
203135
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
204136
period_ns, std::move(callback), node_base->get_context());
205137
node_timers->add_timer(timer, group);
206138
return timer;
207139
}
140+
208141
} // namespace rclcpp
209142

210143
#endif // RCLCPP__CREATE_TIMER_HPP_

rclcpp/include/rclcpp/node.hpp

Lines changed: 1 addition & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ class Node : public std::enable_shared_from_this<Node>
227227
)
228228
);
229229

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

243-
/// Create a timer that uses the node clock to drive the callback.
244-
/**
245-
* \param[in] period Time interval between triggers of the callback.
246-
* \param[in] callback User-defined callback function.
247-
* \param[in] group Callback group to execute this timer's callback in.
248-
*/
249-
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
250-
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
251-
create_timer(
252-
std::chrono::duration<DurationRepT, DurationT> period,
253-
CallbackT callback,
254-
rclcpp::CallbackGroup::SharedPtr group = nullptr);
255-
256243
/// Create and return a Client.
257244
/**
258245
* \param[in] service_name The topic to service on.

rclcpp/include/rclcpp/node_impl.hpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -120,22 +120,6 @@ Node::create_wall_timer(
120120
this->node_timers_.get());
121121
}
122122

123-
template<typename DurationRepT, typename DurationT, typename CallbackT>
124-
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
125-
Node::create_timer(
126-
std::chrono::duration<DurationRepT, DurationT> period,
127-
CallbackT callback,
128-
rclcpp::CallbackGroup::SharedPtr group)
129-
{
130-
return rclcpp::create_timer(
131-
this->get_clock(),
132-
period,
133-
std::move(callback),
134-
group,
135-
this->node_base_.get(),
136-
this->node_timers_.get());
137-
}
138-
139123
template<typename ServiceT>
140124
typename Client<ServiceT>::SharedPtr
141125
Node::create_client(

rclcpp/test/rclcpp/test_create_timer.cpp

Lines changed: 1 addition & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ TEST(TestCreateTimer, call_with_node_wrapper_compiles)
6262
rclcpp::shutdown();
6363
}
6464

65-
TEST(TestCreateWallTimer, call_wall_timer_with_bad_arguments)
65+
TEST(TestCreateTimer, call_wall_timer_with_bad_arguments)
6666
{
6767
rclcpp::init(0, nullptr);
6868
NodeWrapper node("test_create_wall_timers_with_bad_arguments");
@@ -117,66 +117,6 @@ TEST(TestCreateWallTimer, call_wall_timer_with_bad_arguments)
117117
rclcpp::shutdown();
118118
}
119119

120-
TEST(TestCreateTimer, call_timer_with_bad_arguments)
121-
{
122-
rclcpp::init(0, nullptr);
123-
NodeWrapper node("test_create_timers_with_bad_arguments");
124-
auto callback = []() {};
125-
rclcpp::CallbackGroup::SharedPtr group = nullptr;
126-
auto node_interface =
127-
rclcpp::node_interfaces::get_node_base_interface(node).get();
128-
auto timers_interface =
129-
rclcpp::node_interfaces::get_node_timers_interface(node).get();
130-
131-
auto clock = node.get_node_clock_interface()->get_clock();
132-
133-
// Negative period
134-
EXPECT_THROW(
135-
rclcpp::create_timer(
136-
clock, -1ms, callback, group, node_interface, timers_interface),
137-
std::invalid_argument);
138-
139-
// Very negative period
140-
constexpr auto nanoseconds_min = std::chrono::nanoseconds::min();
141-
EXPECT_THROW(
142-
rclcpp::create_timer(
143-
clock, nanoseconds_min, callback, group, node_interface, timers_interface),
144-
std::invalid_argument);
145-
146-
// Period must be less than nanoseconds::max()
147-
constexpr auto nanoseconds_max = std::chrono::nanoseconds::min();
148-
EXPECT_THROW(
149-
rclcpp::create_timer(
150-
clock, nanoseconds_max, callback, group, node_interface, timers_interface),
151-
std::invalid_argument);
152-
153-
EXPECT_NO_THROW(
154-
rclcpp::create_timer(
155-
clock, nanoseconds_max - 1us, callback, group, node_interface, timers_interface));
156-
157-
EXPECT_NO_THROW(
158-
rclcpp::create_timer(clock, 0ms, callback, group, node_interface, timers_interface));
159-
160-
// Period must be less than nanoseconds::max()
161-
constexpr auto hours_max = std::chrono::hours::max();
162-
EXPECT_THROW(
163-
rclcpp::create_timer(
164-
clock, hours_max, callback, group, node_interface, timers_interface),
165-
std::invalid_argument);
166-
167-
// node_interface is null
168-
EXPECT_THROW(
169-
rclcpp::create_timer(clock, 1ms, callback, group, nullptr, timers_interface),
170-
std::invalid_argument);
171-
172-
// timers_interface is null
173-
EXPECT_THROW(
174-
rclcpp::create_timer(clock, 1ms, callback, group, node_interface, nullptr),
175-
std::invalid_argument);
176-
177-
rclcpp::shutdown();
178-
}
179-
180120
static void test_timer_callback(void) {}
181121

182122
TEST(TestCreateTimer, timer_function_pointer)

0 commit comments

Comments
 (0)