Skip to content

Commit c9a0ab9

Browse files
authored
add logic for 'params_file' to handle both string and string_array (#1898)
1 parent 73fe227 commit c9a0ab9

File tree

3 files changed

+64
-17
lines changed

3 files changed

+64
-17
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 25 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -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

controller_manager/test/test_spawner_unspawner.cpp

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -255,6 +255,44 @@ TEST_F(TestLoadController, multi_ctrls_test_type_in_param)
255255
}
256256
}
257257

258+
TEST_F(TestLoadController, spawner_test_with_params_file_string_parameter)
259+
{
260+
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
261+
"/test/test_controller_spawner_with_type.yaml";
262+
263+
cm_->set_parameter(rclcpp::Parameter(
264+
"ctrl_with_parameters_and_type.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
265+
cm_->set_parameter(
266+
rclcpp::Parameter("ctrl_with_parameters_and_type.params_file", test_file_path));
267+
268+
ControllerManagerRunner cm_runner(this);
269+
// Provide controller type via the parsed file
270+
EXPECT_EQ(
271+
call_spawner("ctrl_with_parameters_and_type --load-only -c test_controller_manager"), 0);
272+
273+
ASSERT_EQ(cm_->get_loaded_controllers().size(), 1ul);
274+
275+
auto ctrl_with_parameters_and_type = cm_->get_loaded_controllers()[0];
276+
ASSERT_EQ(ctrl_with_parameters_and_type.info.name, "ctrl_with_parameters_and_type");
277+
ASSERT_EQ(ctrl_with_parameters_and_type.info.type, test_controller::TEST_CONTROLLER_CLASS_NAME);
278+
ASSERT_EQ(
279+
ctrl_with_parameters_and_type.c->get_lifecycle_state().id(),
280+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
281+
ASSERT_EQ(
282+
cm_->get_parameter("ctrl_with_parameters_and_type.params_file").as_string(), test_file_path);
283+
auto ctrl_node = ctrl_with_parameters_and_type.c->get_node();
284+
ASSERT_THAT(
285+
ctrl_with_parameters_and_type.info.parameters_files,
286+
std::vector<std::string>({test_file_path}));
287+
if (!ctrl_node->has_parameter("joint_names"))
288+
{
289+
ctrl_node->declare_parameter("joint_names", std::vector<std::string>({"random_joint"}));
290+
}
291+
ASSERT_THAT(
292+
ctrl_node->get_parameter("joint_names").as_string_array(),
293+
std::vector<std::string>({"joint0"}));
294+
}
295+
258296
TEST_F(TestLoadController, spawner_test_type_in_params_file)
259297
{
260298
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +

hardware_interface/include/hardware_interface/controller_info.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ struct ControllerInfo
3434
std::string type;
3535

3636
/// Controller param file
37-
std::optional<std::vector<std::string>> parameters_files;
37+
std::vector<std::string> parameters_files;
3838

3939
/// List of claimed interfaces by the controller.
4040
std::vector<std::string> claimed_interfaces;

0 commit comments

Comments
 (0)