Skip to content

Commit

Permalink
LifecycleNode bugfix and add test cases (#2562)
Browse files Browse the repository at this point in the history
* LifecycleNode base class resource needs to be reset via dtor.

Signed-off-by: Tomoya Fujita <[email protected]>

* add debug notice that prints LifecycleNode is not shutdown in dtor.

  Currently it is user application responsibility to manage the all state control.
  See more details for #2520.

Signed-off-by: Tomoya Fujita <[email protected]>

* add test cases to call shutdown from each primary state.

Signed-off-by: Tomoya Fujita <[email protected]>

* address review comments.

Signed-off-by: Tomoya Fujita <[email protected]>

---------

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya authored Sep 12, 2024
1 parent 1a3dfaf commit 97c386c
Show file tree
Hide file tree
Showing 2 changed files with 77 additions and 0 deletions.
12 changes: 12 additions & 0 deletions rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,8 +152,19 @@ LifecycleNode::LifecycleNode(

LifecycleNode::~LifecycleNode()
{
auto current_state = LifecycleNode::get_current_state().id();
if (current_state != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) {
// This might be leaving sensors and devices without shutting down unintentionally.
// It is user's responsibility to call shutdown to avoid leaving them unknow states.
RCLCPP_WARN(
rclcpp::get_logger("rclcpp_lifecycle"),
"LifecycleNode is not shut down: Node still in state(%u) in destructor",
current_state);
}

// release sub-interfaces in an order that allows them to consult with node_base during tear-down
node_waitables_.reset();
node_type_descriptions_.reset();
node_time_source_.reset();
node_parameters_.reset();
node_clock_.reset();
Expand All @@ -162,6 +173,7 @@ LifecycleNode::~LifecycleNode()
node_timers_.reset();
node_logging_.reset();
node_graph_.reset();
node_base_.reset();
}

const char *
Expand Down
65 changes: 65 additions & 0 deletions rclcpp_lifecycle/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,6 +431,71 @@ TEST_F(TestDefaultStateMachine, bad_mood) {
EXPECT_EQ(1u, test_node->number_of_callbacks);
}

TEST_F(TestDefaultStateMachine, shutdown_from_each_primary_state) {
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;

// PRIMARY_STATE_UNCONFIGURED to shutdown
{
auto ret = reset_key;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto finalized = test_node->shutdown(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
}

// PRIMARY_STATE_INACTIVE to shutdown
{
auto ret = reset_key;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto configured = test_node->configure(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(configured.id(), State::PRIMARY_STATE_INACTIVE);
ret = reset_key;
auto finalized = test_node->shutdown(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
}

// PRIMARY_STATE_ACTIVE to shutdown
{
auto ret = reset_key;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto configured = test_node->configure(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(configured.id(), State::PRIMARY_STATE_INACTIVE);
ret = reset_key;
auto activated = test_node->activate(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(activated.id(), State::PRIMARY_STATE_ACTIVE);
ret = reset_key;
auto finalized = test_node->shutdown(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
}

// PRIMARY_STATE_FINALIZED to shutdown
{
auto ret = reset_key;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto configured = test_node->configure(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(configured.id(), State::PRIMARY_STATE_INACTIVE);
ret = reset_key;
auto activated = test_node->activate(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(activated.id(), State::PRIMARY_STATE_ACTIVE);
ret = reset_key;
auto finalized = test_node->shutdown(ret);
EXPECT_EQ(success, ret);
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
ret = reset_key;
auto finalized_again = test_node->shutdown(ret);
EXPECT_EQ(reset_key, ret);
EXPECT_EQ(finalized_again.id(), State::PRIMARY_STATE_FINALIZED);
}
}

TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");

Expand Down

0 comments on commit 97c386c

Please sign in to comment.