From 9b654942f99f17850e0e95480958abdbb508bc00 Mon Sep 17 00:00:00 2001 From: Romain DESILLE Date: Wed, 30 Oct 2024 12:45:19 +0100 Subject: [PATCH] Fix NodeOptions assignment operator (#2656) * Fix NodeOptions assignment operator Also copy the enable_logger_service_ member during the assignment operation * Add more checks for NodeOptions copy test * Set non default values by avoiding the copy-assignement Signed-off-by: Romain DESILLE Co-authored-by: Christophe Bedard --- rclcpp/src/rclcpp/node_options.cpp | 1 + rclcpp/test/rclcpp/test_node_options.cpp | 51 ++++++++++++++++++++++++ 2 files changed, 52 insertions(+) diff --git a/rclcpp/src/rclcpp/node_options.cpp b/rclcpp/src/rclcpp/node_options.cpp index ada87ce5fe..ca58154eb4 100644 --- a/rclcpp/src/rclcpp/node_options.cpp +++ b/rclcpp/src/rclcpp/node_options.cpp @@ -80,6 +80,7 @@ NodeOptions::operator=(const NodeOptions & other) this->clock_type_ = other.clock_type_; this->clock_qos_ = other.clock_qos_; this->use_clock_thread_ = other.use_clock_thread_; + this->enable_logger_service_ = other.enable_logger_service_; this->parameter_event_qos_ = other.parameter_event_qos_; this->rosout_qos_ = other.rosout_qos_; this->parameter_event_publisher_options_ = other.parameter_event_publisher_options_; diff --git a/rclcpp/test/rclcpp/test_node_options.cpp b/rclcpp/test/rclcpp/test_node_options.cpp index 49af93aa8a..7abc36f38e 100644 --- a/rclcpp/test/rclcpp/test_node_options.cpp +++ b/rclcpp/test/rclcpp/test_node_options.cpp @@ -200,6 +200,57 @@ TEST(TestNodeOptions, copy) { rcl_arguments_get_count_unparsed(&other_rcl_options->arguments), rcl_arguments_get_count_unparsed(&rcl_options->arguments)); } + + { + // The following scope test is missing: + // "arguments" because it is already tested in the above scopes + // "parameter_event_publisher_options" because it can not be directly compared with EXPECT_EQ + // "allocator" because it can not be directly compared with EXPECT_EQ + + // 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. + auto non_default_options = rclcpp::NodeOptions(); + non_default_options + .parameter_overrides({rclcpp::Parameter("foo", 0), rclcpp::Parameter("bar", "1")}) + .use_global_arguments(false) + .enable_rosout(false) + .use_intra_process_comms(true) + .enable_topic_statistics(true) + .start_parameter_services(false) + .enable_logger_service(true) + .start_parameter_event_publisher(false) + .clock_type(RCL_SYSTEM_TIME) + .clock_qos(rclcpp::SensorDataQoS()) + .use_clock_thread(false) + .parameter_event_qos(rclcpp::ClockQoS()) + .rosout_qos(rclcpp::ParameterEventsQoS()) + .allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true); + + auto copied_options = non_default_options; + EXPECT_EQ(non_default_options.parameter_overrides(), copied_options.parameter_overrides()); + EXPECT_EQ(non_default_options.use_global_arguments(), copied_options.use_global_arguments()); + EXPECT_EQ(non_default_options.enable_rosout(), copied_options.enable_rosout()); + EXPECT_EQ(non_default_options.use_intra_process_comms(), + copied_options.use_intra_process_comms()); + EXPECT_EQ(non_default_options.enable_topic_statistics(), + copied_options.enable_topic_statistics()); + EXPECT_EQ(non_default_options.start_parameter_services(), + copied_options.start_parameter_services()); + EXPECT_EQ(non_default_options.enable_logger_service(), copied_options.enable_logger_service()); + EXPECT_EQ(non_default_options.start_parameter_event_publisher(), + copied_options.start_parameter_event_publisher()); + EXPECT_EQ(non_default_options.clock_type(), copied_options.clock_type()); + EXPECT_EQ(non_default_options.clock_qos(), copied_options.clock_qos()); + EXPECT_EQ(non_default_options.use_clock_thread(), copied_options.use_clock_thread()); + EXPECT_EQ(non_default_options.parameter_event_qos(), copied_options.parameter_event_qos()); + EXPECT_EQ(non_default_options.rosout_qos(), copied_options.rosout_qos()); + EXPECT_EQ(non_default_options.allow_undeclared_parameters(), + copied_options.allow_undeclared_parameters()); + EXPECT_EQ(non_default_options.automatically_declare_parameters_from_overrides(), + copied_options.automatically_declare_parameters_from_overrides()); + } } TEST(TestNodeOptions, append_parameter_override) {