@@ -551,16 +551,28 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c
551551 // read_only params, dynamic maps lists etc
552552 // Now check if the parameters_file parameter exist
553553 const std::string param_name = controller_name + " .params_file" ;
554- std::vector<std::string> parameters_files;
554+ controller_spec. info . parameters_files . clear () ;
555555
556- // Check if parameter has been declared
557- if (!has_parameter (param_name))
556+ // get_parameter checks if parameter has been declared/set
557+ rclcpp::Parameter params_files_parameter;
558+ if (get_parameter (param_name, params_files_parameter))
558559 {
559- declare_parameter (param_name, rclcpp::ParameterType::PARAMETER_STRING_ARRAY);
560- }
561- if (get_parameter (param_name, parameters_files) && !parameters_files.empty ())
562- {
563- controller_spec.info .parameters_files = parameters_files;
560+ if (params_files_parameter.get_type () == rclcpp::ParameterType::PARAMETER_STRING_ARRAY)
561+ {
562+ controller_spec.info .parameters_files = params_files_parameter.as_string_array ();
563+ }
564+ else if (params_files_parameter.get_type () == rclcpp::ParameterType::PARAMETER_STRING)
565+ {
566+ controller_spec.info .parameters_files .push_back (params_files_parameter.as_string ());
567+ }
568+ else
569+ {
570+ RCLCPP_ERROR (
571+ get_logger (),
572+ " The 'params_file' param needs to be a string or a string array for '%s', but it is of "
573+ " type %s" ,
574+ controller_name.c_str (), params_files_parameter.get_type_name ().c_str ());
575+ }
564576 }
565577
566578 const std::string fallback_ctrl_param = controller_name + " .fallback_controllers" ;
@@ -3250,17 +3262,14 @@ rclcpp::NodeOptions ControllerManager::determine_controller_node_options(
32503262 node_options_arguments.push_back (arg);
32513263 }
32523264
3253- if ( controller.info .parameters_files . has_value () )
3265+ for ( const auto & parameters_file : controller.info .parameters_files )
32543266 {
3255- for ( const auto & parameters_file : controller. info . parameters_files . value ( ))
3267+ if (! check_for_element (node_options_arguments, RCL_ROS_ARGS_FLAG ))
32563268 {
3257- if (!check_for_element (node_options_arguments, RCL_ROS_ARGS_FLAG))
3258- {
3259- node_options_arguments.push_back (RCL_ROS_ARGS_FLAG);
3260- }
3261- node_options_arguments.push_back (RCL_PARAM_FILE_FLAG);
3262- node_options_arguments.push_back (parameters_file);
3269+ node_options_arguments.push_back (RCL_ROS_ARGS_FLAG);
32633270 }
3271+ node_options_arguments.push_back (RCL_PARAM_FILE_FLAG);
3272+ node_options_arguments.push_back (parameters_file);
32643273 }
32653274
32663275 // ensure controller's `use_sim_time` parameter matches controller_manager's
0 commit comments