Skip to content

Commit dceb612

Browse files
authored
lifecycle node dtor shutdown should be called only in primary state. (#2543)
* lifecycle node dtor shutdown should be called only in primary state. Signed-off-by: Tomoya Fujita <[email protected]> * LifecycleNode shutdown on dtor only with valid context. (#2545) Signed-off-by: Tomoya Fujita <[email protected]> --------- Signed-off-by: Tomoya Fujita <[email protected]>
1 parent 753a29b commit dceb612

File tree

1 file changed

+25
-12
lines changed

1 file changed

+25
-12
lines changed

rclcpp_lifecycle/src/lifecycle_node.cpp

Lines changed: 25 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -146,20 +146,32 @@ LifecycleNode::LifecycleNode(
146146

147147
LifecycleNode::~LifecycleNode()
148148
{
149-
// shutdown if necessary to avoid leaving the device in unknown state
150-
if (LifecycleNode::get_current_state().id() !=
151-
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
152-
{
153-
auto ret = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
154-
auto finalized = LifecycleNode::shutdown(ret);
155-
if (finalized.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED ||
156-
ret != rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS)
157-
{
158-
RCLCPP_WARN(
149+
auto current_state = LifecycleNode::get_current_state().id();
150+
// shutdown if necessary to avoid leaving the device in any other primary state
151+
if (current_state < lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) {
152+
if (node_base_->get_context()->is_valid()) {
153+
auto ret = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
154+
auto finalized = LifecycleNode::shutdown(ret);
155+
if (finalized.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED ||
156+
ret != rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS)
157+
{
158+
RCLCPP_WARN(
159+
rclcpp::get_logger("rclcpp_lifecycle"),
160+
"Shutdown error in destruction of LifecycleNode: final state(%s)",
161+
finalized.label().c_str());
162+
}
163+
} else {
164+
// TODO(fujitatomoya): consider when context is gracefully shutdown before.
165+
RCLCPP_DEBUG(
159166
rclcpp::get_logger("rclcpp_lifecycle"),
160-
"Shutdown error in destruction of LifecycleNode: final state(%s)",
161-
finalized.label().c_str());
167+
"Context invalid error in destruction of LifecycleNode: Node still in transition state(%u)",
168+
current_state);
162169
}
170+
} else if (current_state > lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) {
171+
RCLCPP_WARN(
172+
rclcpp::get_logger("rclcpp_lifecycle"),
173+
"Shutdown error in destruction of LifecycleNode: Node still in transition state(%u)",
174+
current_state);
163175
}
164176

165177
// release sub-interfaces in an order that allows them to consult with node_base during tear-down
@@ -172,6 +184,7 @@ LifecycleNode::~LifecycleNode()
172184
node_timers_.reset();
173185
node_logging_.reset();
174186
node_graph_.reset();
187+
node_base_.reset();
175188
}
176189

177190
const char *

0 commit comments

Comments
 (0)