Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Trigger shutdown transition in destructor #1979

Merged
merged 11 commits into from
Jan 9, 2025
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
public:
ControllerInterfaceBase() = default;

virtual ~ControllerInterfaceBase() = default;
virtual ~ControllerInterfaceBase();

/// Get configuration for controller's required command interfaces.
/**
Expand Down
25 changes: 25 additions & 0 deletions controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,22 @@

namespace controller_interface
{
ControllerInterfaceBase::~ControllerInterfaceBase()
{
// check if node is initialized and we still have a valid context
if (
node_.get() &&
get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED &&
rclcpp::ok())
{
RCLCPP_DEBUG(
get_node()->get_logger(),
"Calling shutdown transition of controller node '%s' due to destruction.",
get_node()->get_name());
node_->shutdown();
}
}

return_type ControllerInterfaceBase::init(
const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
const std::string & node_namespace, const rclcpp::NodeOptions & node_options)
Expand Down Expand Up @@ -52,6 +68,11 @@ return_type ControllerInterfaceBase::init(
break;
case LifecycleNodeInterface::CallbackReturn::ERROR:
case LifecycleNodeInterface::CallbackReturn::FAILURE:
RCLCPP_DEBUG(
get_node()->get_logger(),
"Calling shutdown transition of controller node '%s' due to init failure.",
get_node()->get_name());
node_->shutdown();
return return_type::ERROR;
}

Expand Down Expand Up @@ -158,6 +179,10 @@ void ControllerInterfaceBase::release_interfaces()

const rclcpp_lifecycle::State & ControllerInterfaceBase::get_lifecycle_state() const
{
if (!node_.get())
{
throw std::runtime_error("Lifecycle node hasn't been initialized yet!");
}
return node_->get_current_state();
}

Expand Down
12 changes: 12 additions & 0 deletions controller_interface/test/test_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,17 @@ TEST(TestableControllerInterface, init)

// try to get node when not initialized
ASSERT_THROW(controller.get_node(), std::runtime_error);
ASSERT_THROW(const auto node = controller.get_node(), std::runtime_error);
ASSERT_THROW(controller.get_lifecycle_state(), std::runtime_error);

// initialize, create node
const auto node_options = controller.define_custom_node_options();
ASSERT_EQ(
controller.init(TEST_CONTROLLER_NAME, "", 10.0, "", node_options),
controller_interface::return_type::OK);
ASSERT_NO_THROW(controller.get_node());
ASSERT_NO_THROW(const auto node = controller.get_node());
ASSERT_NO_THROW(controller.get_lifecycle_state());

// update_rate is set to controller_manager's rate
ASSERT_EQ(controller.get_update_rate(), 10u);
Expand All @@ -54,6 +58,7 @@ TEST(TestableControllerInterface, init)
controller.configure();
ASSERT_EQ(controller.get_update_rate(), 10u);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -80,6 +85,8 @@ TEST(TestableControllerInterface, setting_negative_update_rate_in_configure)
// The configure should fail and the update rate should stay the same
ASSERT_EQ(controller.configure().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
ASSERT_EQ(controller.get_update_rate(), 1000u);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand Down Expand Up @@ -149,6 +156,7 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure)
ASSERT_EQ(controller.get_update_rate(), 623u);

executor->cancel();
controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -166,6 +174,8 @@ TEST(TestableControllerInterfaceInitError, init_with_error)
controller.init(TEST_CONTROLLER_NAME, "", 100.0, "", node_options),
controller_interface::return_type::ERROR);

ASSERT_EQ(
controller.get_lifecycle_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
rclcpp::shutdown();
}

Expand All @@ -183,6 +193,8 @@ TEST(TestableControllerInterfaceInitFailure, init_with_failure)
controller.init(TEST_CONTROLLER_NAME, "", 50.0, "", node_options),
controller_interface::return_type::ERROR);

ASSERT_EQ(
controller.get_lifecycle_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
rclcpp::shutdown();
}

Expand Down
19 changes: 14 additions & 5 deletions controller_interface/test/test_controller_with_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ TEST(ControllerWithOption, init_with_overrides)
rclcpp::init(argc, argv);
// creates the controller
FriendControllerWithOptions controller;
EXPECT_EQ(
ASSERT_EQ(
controller.init("controller_name", "", 50.0, "", controller.define_custom_node_options()),
controller_interface::return_type::OK);
// checks that the node options have been updated
Expand All @@ -54,6 +54,8 @@ TEST(ControllerWithOption, init_with_overrides)
EXPECT_EQ(controller.params["parameter1"], 1.);
EXPECT_EQ(controller.params["parameter2"], 2.);
EXPECT_EQ(controller.params["parameter3"], 3.);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -68,7 +70,7 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters)
controller_node_options.arguments(
{"--ros-args", "-p", "parameter_list.parameter1:=1.", "-p", "parameter_list.parameter2:=2.",
"-p", "parameter_list.parameter3:=3."});
EXPECT_EQ(
ASSERT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
Expand All @@ -81,6 +83,8 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters)
EXPECT_EQ(controller.params["parameter1"], 1.);
EXPECT_EQ(controller.params["parameter2"], 2.);
EXPECT_EQ(controller.params["parameter3"], 3.);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -96,7 +100,7 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters_file)
std::cerr << params_file_path << std::endl;
auto controller_node_options = controller.define_custom_node_options();
controller_node_options.arguments({"--ros-args", "--params-file", params_file_path});
EXPECT_EQ(
ASSERT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
Expand All @@ -112,6 +116,8 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters_file)
bool use_sim_time(true);
controller.get_node()->get_parameter_or("use_sim_time", use_sim_time, false);
ASSERT_FALSE(use_sim_time);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -130,7 +136,7 @@ TEST(
controller_node_options.arguments(
{"--ros-args", "--params-file", params_file_path, "-p", "parameter_list.parameter1:=562.785",
"-p", "use_sim_time:=true"});
EXPECT_EQ(
ASSERT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
Expand All @@ -146,6 +152,8 @@ TEST(
bool use_sim_time(false);
controller.get_node()->get_parameter_or("use_sim_time", use_sim_time, false);
ASSERT_TRUE(use_sim_time);

controller.get_node()->shutdown();
rclcpp::shutdown();
}

Expand All @@ -157,7 +165,7 @@ TEST(ControllerWithOption, init_without_overrides)
rclcpp::init(argc, argv);
// creates the controller
FriendControllerWithOptions controller;
EXPECT_EQ(
ASSERT_EQ(
controller.init("controller_name", "", 50.0, "", controller.define_custom_node_options()),
controller_interface::return_type::ERROR);
// checks that the node options have been updated
Expand All @@ -166,5 +174,6 @@ TEST(ControllerWithOption, init_without_overrides)
EXPECT_TRUE(node_options.automatically_declare_parameters_from_overrides());
// checks that no parameter has been declared from overrides
EXPECT_EQ(controller.params.size(), 0u);

rclcpp::shutdown();
}
13 changes: 12 additions & 1 deletion joint_limits/test/joint_limits_rosparam_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <gtest/gtest.h>

#include "joint_limits/joint_limits_rosparam.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

class JointLimitsRosParamTest : public ::testing::Test
Expand Down Expand Up @@ -294,7 +295,17 @@ class JointLimitsLifecycleNodeUndeclaredRosParamTest : public ::testing::Test
lifecycle_node_ = rclcpp_lifecycle::LifecycleNode::make_shared("JointLimitsRosparamTestNode");
}

void TearDown() { lifecycle_node_.reset(); }
void TearDown()
{
if (
lifecycle_node_->get_current_state().id() !=
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED &&
rclcpp::ok())
{
lifecycle_node_->shutdown();
}
lifecycle_node_.reset();
}

protected:
rclcpp_lifecycle::LifecycleNode::SharedPtr lifecycle_node_;
Expand Down
Loading