Skip to content

Commit

Permalink
Use the controller NodeOptions to be able to load the params on Node …
Browse files Browse the repository at this point in the history
…creation
  • Loading branch information
saikishor committed Jan 13, 2024
1 parent ae67a26 commit 512424d
Showing 1 changed file with 8 additions and 2 deletions.
10 changes: 8 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1317,10 +1317,16 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::add_co
return nullptr;
}

rclcpp::NodeOptions controller_node_options = rclcpp::NodeOptions().enable_logger_service(true);
if (controller.info.params_file.has_value())
{
controller_node_options = controller_node_options.arguments(
{"--ros-args", "--params-file", controller.info.params_file.value()});
}
if (
controller.c->init(
controller.info.name, robot_description_, get_update_rate(), get_namespace()) ==
controller_interface::return_type::ERROR)
controller.info.name, robot_description_, get_update_rate(), get_namespace(),
controller_node_options) == controller_interface::return_type::ERROR)
{
to.clear();
RCLCPP_ERROR(
Expand Down

0 comments on commit 512424d

Please sign in to comment.