Skip to content

Commit

Permalink
update tests to use the new get_node_options API
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 15, 2023
1 parent ffe5e5e commit 63dafed
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 22 deletions.
15 changes: 9 additions & 6 deletions controller_interface/test/test_controller_with_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,9 @@ class ControllerWithOptions : public controller_interface::ControllerInterface

controller_interface::return_type init(
const std::string & controller_name, const std::string & urdf,
const std::string & namespace_ = "",
const rclcpp::NodeOptions & node_options =
rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)) override
const std::string & namespace_ = "") override
{
ControllerInterface::init(controller_name, urdf, namespace_, node_options);
ControllerInterface::init(controller_name, urdf, namespace_);

switch (on_init())
{
Expand All @@ -68,6 +64,13 @@ class ControllerWithOptions : public controller_interface::ControllerInterface
}
}

rclcpp::NodeOptions get_node_options() const override
{
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true);
}

controller_interface::InterfaceConfiguration command_interface_configuration() const override
{
return controller_interface::InterfaceConfiguration{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,6 @@ TestControllerFailedInit::on_init()
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
}

controller_interface::return_type TestControllerFailedInit::init(
const std::string & /* controller_name */, const std::string & /* urdf */,
const std::string & /*namespace_*/, const rclcpp::NodeOptions & /*node_options*/)
{
return controller_interface::return_type::ERROR;
}

controller_interface::return_type TestControllerFailedInit::update(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,21 +38,19 @@ class TestControllerFailedInit : public controller_interface::ControllerInterfac
CONTROLLER_MANAGER_PUBLIC
virtual ~TestControllerFailedInit() = default;

CONTROLLER_INTERFACE_PUBLIC
controller_interface::return_type init(
const std::string & controller_name, const std::string & urdf,
const std::string & namespace_ = "",
const rclcpp::NodeOptions & node_options =
rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)) override;

controller_interface::InterfaceConfiguration command_interface_configuration() const override
{
return controller_interface::InterfaceConfiguration{
controller_interface::interface_configuration_type::NONE};
}

rclcpp::NodeOptions get_node_options() const override
{
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true);
}

controller_interface::InterfaceConfiguration state_interface_configuration() const override
{
return controller_interface::InterfaceConfiguration{
Expand Down

0 comments on commit 63dafed

Please sign in to comment.