Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 10 additions & 4 deletions rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
constexpr bool publish_update = true;
State initial_state;
unsigned int current_state_id;
rcl_lifecycle_transition_t const * original_transition{nullptr};

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
Expand All @@ -414,6 +415,9 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
// keep the initial state to pass to a transition callback
initial_state = State(state_machine_.current_state);

original_transition =
rcl_lifecycle_get_transition_by_id(state_machine_.current_state, transition_id);

if (
rcl_lifecycle_trigger_transition_by_id(
&state_machine_, transition_id, publish_update) != RCL_RET_OK)
Expand Down Expand Up @@ -458,12 +462,14 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
current_state_id = state_machine_.current_state->id;
}

// error handling ?!
// error handling
// TODO(karsten1987): iterate over possible ret value
if (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR) {
RCLCPP_WARN(
node_logging_interface_->get_logger(),
"Error occurred while doing error handling.");
if (original_transition) {
RCLCPP_WARN(
node_logging_interface_->get_logger(),
"Callback returned ERROR during the transition: %s", original_transition->label);
}
Comment on lines +468 to +472
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@peter-mitrano-ar

thanks for bringing up this question with PR.

i believe this error message is meant to be the error during error handling callback, which is not related to the original transition. so i think original message Error occurred while doing error handling. is appropriate to print here.

btw i thinks error handling is missing some functionalities such as ros2/rcl_interfaces#97

Copy link
Contributor Author

@peter-mitrano-ar peter-mitrano-ar Aug 6, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@fujitatomoya

i believe this error message is meant to be the error during error handling callback

This would be the on_error callback, right? It looks to me like that happens later and has not happened yet. This warning is printed regardless of whether on_error is successful or not.

so i think original message Error occurred while doing error handling. is appropriate

So if a user callback returns ERROR, but on_error has not been called yet, does this message really make sense? I don't think so.

I tested this just to confirm on_error is called after this warning is printed:

[ros2_control_node] [ERROR] [...]: Non-zero gain pd_gains.trans_x.p=1 ...
[ros2_control_node] [WARN] [...]: Callback returned ERROR during the transition: configure
[ros2_control_node] [WARN] [...]: on_error called in lookat controller.

Here is my on-error for testing, as you can see it returns SUCCESS.

  CallbackReturn CartesianLookAtController::on_error(const rclcpp_lifecycle::State& previous_state)
  {
    RCLCPP_WARN(get_node()->get_logger(), "on_error called in lookat controller.");
    return CallbackReturn::SUCCESS;
  }

But perhaps I still not understanding the code? Thank you for you prompt reply and for pointing out that error handling is still missing some things!

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah, sorry you are right. i was the confused here.... thanks for pointing that out!

on_error is not yet called here, transition callback returned error. that said, i agree with you that the error message here is not appropriate. and the later, it will call the on_error callback to see if it can clean up the error state for this transition.


auto error_cb_code = execute_callback(current_state_id, initial_state);
auto error_cb_label = get_label_for_return_code(error_cb_code);
Expand Down