diff --git a/rclcpp/test/rclcpp/test_node_options.cpp b/rclcpp/test/rclcpp/test_node_options.cpp index 2afc3a0406..41159b3a25 100644 --- a/rclcpp/test/rclcpp/test_node_options.cpp +++ b/rclcpp/test/rclcpp/test_node_options.cpp @@ -211,6 +211,7 @@ TEST(TestNodeOptions, copy) { // We separate attribute modification from variable initialisation (copy assignment operator) // to be sure the "non_default_options"'s properties are correctly set before testing the // assignment operator. + rclcpp::init(0, nullptr); rclcpp::Node node("time_sink__test_node"); auto non_default_options = rclcpp::NodeOptions(); non_default_options @@ -254,6 +255,7 @@ TEST(TestNodeOptions, copy) { EXPECT_EQ(non_default_options.automatically_declare_parameters_from_overrides(), copied_options.automatically_declare_parameters_from_overrides()); EXPECT_EQ(non_default_options.time_source(), copied_options.time_source()); + rclcpp::shutdown(); } }