Skip to content

Commit 9c156fe

Browse files
committed
Add 'time_source' to 'NodeOptions' copy test
Signed-off-by: Patrick Roncagliolo <[email protected]>
1 parent a7d891f commit 9c156fe

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

rclcpp/test/rclcpp/test_node_options.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "rcl/arguments.h"
2323
#include "rcl/remap.h"
2424

25+
#include "rclcpp/node.hpp"
2526
#include "rclcpp/node_options.hpp"
2627

2728
#include "../mocking_utils/patch.hpp"
@@ -210,6 +211,7 @@ TEST(TestNodeOptions, copy) {
210211
// We separate attribute modification from variable initialisation (copy assignment operator)
211212
// to be sure the "non_default_options"'s properties are correctly set before testing the
212213
// assignment operator.
214+
rclcpp::Node node("time_sink__test_node");
213215
auto non_default_options = rclcpp::NodeOptions();
214216
non_default_options
215217
.parameter_overrides({rclcpp::Parameter("foo", 0), rclcpp::Parameter("bar", "1")})
@@ -226,7 +228,8 @@ TEST(TestNodeOptions, copy) {
226228
.parameter_event_qos(rclcpp::ClockQoS())
227229
.rosout_qos(rclcpp::ParameterEventsQoS())
228230
.allow_undeclared_parameters(true)
229-
.automatically_declare_parameters_from_overrides(true);
231+
.automatically_declare_parameters_from_overrides(true)
232+
.time_source(node->get_node_time_source_interface());
230233

231234
auto copied_options = non_default_options;
232235
EXPECT_EQ(non_default_options.parameter_overrides(), copied_options.parameter_overrides());
@@ -250,6 +253,7 @@ TEST(TestNodeOptions, copy) {
250253
copied_options.allow_undeclared_parameters());
251254
EXPECT_EQ(non_default_options.automatically_declare_parameters_from_overrides(),
252255
copied_options.automatically_declare_parameters_from_overrides());
256+
EXPECT_EQ(non_default_options.time_source(), copied_options.time_source());
253257
}
254258
}
255259

0 commit comments

Comments
 (0)