From 17113cafd1cf67194628cbcf040165622bd29c74 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 22 Jul 2024 16:53:31 -0700 Subject: [PATCH 1/2] catch the RCLError exception during transition and print error. Signed-off-by: Tomoya Fujita --- rclpy/rclpy/lifecycle/node.py | 28 +++++++++++++++++++++++----- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/rclpy/rclpy/lifecycle/node.py b/rclpy/rclpy/lifecycle/node.py index 6528007d5..a0d82af57 100644 --- a/rclpy/rclpy/lifecycle/node.py +++ b/rclpy/rclpy/lifecycle/node.py @@ -62,6 +62,7 @@ def __init__( :param callback_group: Callback group that will be used by all the lifecycle node services. """ + self._logger = self.get_logger() self._callbacks: Dict[int, Callable[[LifecycleState], TransitionCallbackReturn]] = {} # register all state machine transition callbacks self.__register_callback( @@ -323,18 +324,35 @@ def __change_state(self, transition_id: int) -> TransitionCallbackReturn: self.__check_is_initialized() initial_state = self._state_machine.current_state initial_state = LifecycleState(state_id=initial_state[0], label=initial_state[1]) - self._state_machine.trigger_transition_by_id(transition_id, True) - + try: + self._state_machine.trigger_transition_by_id(transition_id, True) + except _rclpy.RCLError: + self._logger.error( + 'Unable to start transition {0} from current state {1}' + .format(transition_id, self._state_machine.current_state)) + return TransitionCallbackReturn.ERROR cb_return_code = self.__execute_callback( self._state_machine.current_state[0], initial_state) - self._state_machine.trigger_transition_by_label(cb_return_code.to_label(), True) - + try: + self._state_machine.trigger_transition_by_label(cb_return_code.to_label(), True) + except _rclpy.RCLError: + self._logger.error( + 'Failed to complete transition {0}, current state is {1}' + .format(transition_id, self._state_machine.current_state)) + return TransitionCallbackReturn.ERROR if cb_return_code == TransitionCallbackReturn.ERROR: # Now we're in the errorprocessing state, trigger the on_error callback # and transition again based on the return code. error_cb_ret_code = self.__execute_callback( self._state_machine.current_state[0], initial_state) - self._state_machine.trigger_transition_by_label(error_cb_ret_code.to_label(), True) + try: + self._state_machine.trigger_transition_by_label(error_cb_ret_code.to_label(), True) + except _rclpy.RCLError: + self._logger.error( + 'Failed to complete transition to {0} during error processing state, ' + 'current state is {1}' + .format(error_cb_ret_code.to_label(), self._state_machine.current_state)) + return TransitionCallbackReturn.ERROR return cb_return_code def __check_is_initialized(self): From 2b1611e077f5c5f740b290bc9317214dc197f720 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 22 Jul 2024 17:14:42 -0700 Subject: [PATCH 2/2] remove a few exception cases from test_lifecycle.py. Signed-off-by: Tomoya Fujita --- rclpy/test/test_lifecycle.py | 7 ------- 1 file changed, 7 deletions(-) diff --git a/rclpy/test/test_lifecycle.py b/rclpy/test/test_lifecycle.py index 2cd425967..aa531eec3 100644 --- a/rclpy/test/test_lifecycle.py +++ b/rclpy/test/test_lifecycle.py @@ -22,7 +22,6 @@ import rclpy from rclpy.executors import SingleThreadedExecutor -from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy from rclpy.lifecycle import LifecycleNode from rclpy.lifecycle import TransitionCallbackReturn from rclpy.node import Node @@ -69,13 +68,7 @@ def test_lifecycle_state_transitions(): assert node.trigger_deactivate() == TransitionCallbackReturn.SUCCESS assert node.trigger_cleanup() == TransitionCallbackReturn.SUCCESS # some that are not possible from the current state - with pytest.raises(_rclpy.RCLError): - node.trigger_activate() - with pytest.raises(_rclpy.RCLError): - node.trigger_deactivate() assert node.trigger_shutdown() == TransitionCallbackReturn.SUCCESS - with pytest.raises(_rclpy.RCLError): - node.trigger_shutdown() node.destroy_node() # Again but trigger shutdown from 'inactive' instead of 'unconfigured' node = LifecycleNode(