Skip to content

Commit

Permalink
rename get_node_option to define_custom_node_options as per review su…
Browse files Browse the repository at this point in the history
…ggestions
  • Loading branch information
saikishor committed Jan 18, 2024
1 parent 90f31c4 commit d20b971
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -159,13 +159,18 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
const std::string & get_robot_description() const;

/**
* Method used by the `init` method to instantiate the Lifecycle node of the controller upon
* loading the controller
* Method used by the controller_manager as a base NodeOptions to instantiate the Lifecycle node
* of the controller upon loading the controller.
*
* \note The controller_manager will add modify these NodeOptions in case, a params file is passed
* by the spawner to load the controller parameters or when controllers are loaded in simulation
* (see ros2_control#1311, ros2_controllers#698 , ros2_controllers#795,ros2_controllers#966 for
* more details)
*
* @returns NodeOptions required for the configuration of the controller lifecycle node
*/
CONTROLLER_INTERFACE_PUBLIC
virtual rclcpp::NodeOptions get_node_options() const
virtual rclcpp::NodeOptions define_custom_node_options() const
{
return rclcpp::NodeOptions().enable_logger_service(true);
}
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ return_type ControllerInterfaceBase::init(
{
urdf_ = urdf;
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
controller_name, node_namespace, get_node_options(),
controller_name, node_namespace, define_custom_node_options(),
false); // disable LifecycleNode service interfaces

try
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/test/test_controller_with_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class ControllerWithOptions : public controller_interface::ControllerInterface
}
}

rclcpp::NodeOptions get_node_options() const override
rclcpp::NodeOptions define_custom_node_options() const override
{
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class TestControllerFailedInit : public controller_interface::ControllerInterfac
controller_interface::interface_configuration_type::NONE};
}

rclcpp::NodeOptions get_node_options() const override
rclcpp::NodeOptions define_custom_node_options() const override
{
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
Expand Down

0 comments on commit d20b971

Please sign in to comment.