-
Notifications
You must be signed in to change notification settings - Fork 522
Description
Bug report
Required Info:
- Operating System: Ubuntu 24.04
- Installation type: Both
- Version or commit hash: iron latest
- DDS implementation: default
- Client library (if applicable): N/A
Steps to reproduce issue
Shutdown transition was added to the lifecycle node destructor in #2450 (iron backport: #2490). This currently triggers shutdown if the node state is anything other than finalized. Would it make sense for this to check whether the node is in one of the primary states before sending the shutdown transition? I've seen the following warning quite a bit when terminating a launched node using ctrl+c.
Unable to start transition 7 from current state shuttingdown: Could not publish transition: publisher's context is invalid, at ./src/rcl/publisher.c:423, at ./src/rcl_lifecycle.c:368
Not sure if it is related to the publisher being invalid or not, but the node is clearly in the shuttingdown state, and not one of the primary states.
Expected behavior
Only attempt transition in primary states unconfigured, inactive, and active.
Actual behavior
Shutdown transition is attempted for intermediate transitions (e.g., shutting down).
Ref. the following destructor snippet
rclcpp/rclcpp_lifecycle/src/lifecycle_node.cpp
Lines 156 to 169 in 5f912eb
| if (LifecycleNode::get_current_state().id() != | |
| lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED) | |
| { | |
| auto ret = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; | |
| auto finalized = LifecycleNode::shutdown(ret); | |
| if (finalized.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED || | |
| ret != rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS) | |
| { | |
| RCLCPP_WARN( | |
| rclcpp::get_logger("rclcpp_lifecycle"), | |
| "Shutdown error in destruction of LifecycleNode: final state(%s)", | |
| finalized.label().c_str()); | |
| } | |
| } |