@@ -200,6 +200,57 @@ TEST(TestNodeOptions, copy) {
200200 rcl_arguments_get_count_unparsed (&other_rcl_options->arguments ),
201201 rcl_arguments_get_count_unparsed (&rcl_options->arguments ));
202202 }
203+
204+ {
205+ // The following scope test is missing:
206+ // "arguments" because it is already tested in the above scopes
207+ // "parameter_event_publisher_options" because it can not be directly compared with EXPECT_EQ
208+ // "allocator" because it can not be directly compared with EXPECT_EQ
209+
210+ // We separate attribute modification from variable initialisation (copy assignment operator)
211+ // to be sure the "non_default_options"'s properties are correctly set before testing the
212+ // assignment operator.
213+ auto non_default_options = rclcpp::NodeOptions ();
214+ non_default_options
215+ .parameter_overrides ({rclcpp::Parameter (" foo" , 0 ), rclcpp::Parameter (" bar" , " 1" )})
216+ .use_global_arguments (false )
217+ .enable_rosout (false )
218+ .use_intra_process_comms (true )
219+ .enable_topic_statistics (true )
220+ .start_parameter_services (false )
221+ .enable_logger_service (true )
222+ .start_parameter_event_publisher (false )
223+ .clock_type (RCL_SYSTEM_TIME)
224+ .clock_qos (rclcpp::SensorDataQoS ())
225+ .use_clock_thread (false )
226+ .parameter_event_qos (rclcpp::ClockQoS ())
227+ .rosout_qos (rclcpp::ParameterEventsQoS ())
228+ .allow_undeclared_parameters (true )
229+ .automatically_declare_parameters_from_overrides (true );
230+
231+ auto copied_options = non_default_options;
232+ EXPECT_EQ (non_default_options.parameter_overrides (), copied_options.parameter_overrides ());
233+ EXPECT_EQ (non_default_options.use_global_arguments (), copied_options.use_global_arguments ());
234+ EXPECT_EQ (non_default_options.enable_rosout (), copied_options.enable_rosout ());
235+ EXPECT_EQ (non_default_options.use_intra_process_comms (),
236+ copied_options.use_intra_process_comms ());
237+ EXPECT_EQ (non_default_options.enable_topic_statistics (),
238+ copied_options.enable_topic_statistics ());
239+ EXPECT_EQ (non_default_options.start_parameter_services (),
240+ copied_options.start_parameter_services ());
241+ EXPECT_EQ (non_default_options.enable_logger_service (), copied_options.enable_logger_service ());
242+ EXPECT_EQ (non_default_options.start_parameter_event_publisher (),
243+ copied_options.start_parameter_event_publisher ());
244+ EXPECT_EQ (non_default_options.clock_type (), copied_options.clock_type ());
245+ EXPECT_EQ (non_default_options.clock_qos (), copied_options.clock_qos ());
246+ EXPECT_EQ (non_default_options.use_clock_thread (), copied_options.use_clock_thread ());
247+ EXPECT_EQ (non_default_options.parameter_event_qos (), copied_options.parameter_event_qos ());
248+ EXPECT_EQ (non_default_options.rosout_qos (), copied_options.rosout_qos ());
249+ EXPECT_EQ (non_default_options.allow_undeclared_parameters (),
250+ copied_options.allow_undeclared_parameters ());
251+ EXPECT_EQ (non_default_options.automatically_declare_parameters_from_overrides (),
252+ copied_options.automatically_declare_parameters_from_overrides ());
253+ }
203254}
204255
205256TEST (TestNodeOptions, append_parameter_override) {
0 commit comments