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,8 @@ 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::init (0 , nullptr );
215+ rclcpp::Node node (" time_sink__test_node" );
213216 auto non_default_options = rclcpp::NodeOptions ();
214217 non_default_options
215218 .parameter_overrides ({rclcpp::Parameter (" foo" , 0 ), rclcpp::Parameter (" bar" , " 1" )})
@@ -226,7 +229,8 @@ TEST(TestNodeOptions, copy) {
226229 .parameter_event_qos (rclcpp::ClockQoS ())
227230 .rosout_qos (rclcpp::ParameterEventsQoS ())
228231 .allow_undeclared_parameters (true )
229- .automatically_declare_parameters_from_overrides (true );
232+ .automatically_declare_parameters_from_overrides (true )
233+ .time_source (node.get_node_time_source_interface ());
230234
231235 auto copied_options = non_default_options;
232236 EXPECT_EQ (non_default_options.parameter_overrides (), copied_options.parameter_overrides ());
@@ -250,6 +254,8 @@ TEST(TestNodeOptions, copy) {
250254 copied_options.allow_undeclared_parameters ());
251255 EXPECT_EQ (non_default_options.automatically_declare_parameters_from_overrides (),
252256 copied_options.automatically_declare_parameters_from_overrides ());
257+ EXPECT_EQ (non_default_options.time_source (), copied_options.time_source ());
258+ rclcpp::shutdown ();
253259 }
254260}
255261
0 commit comments