Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Lifecycle node Transition is not registered exception kills node #1209

Open
mjforan opened this issue Jan 5, 2024 · 5 comments
Open

Lifecycle node Transition is not registered exception kills node #1209

mjforan opened this issue Jan 5, 2024 · 5 comments

Comments

@mjforan
Copy link

mjforan commented Jan 5, 2024

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • binaries (in Docker)
  • Version or commit hash:
    • Humble
  • DDS implementation:
    • rmw_cyclonedds_cpp
  • Client library (if applicable):
    • rclpy

Steps to reproduce issue

The example below is based on the official demo code.

Launch this node and then attempt to execute an invalid transition from the command line, e.g. run the cleanup transition while already in the unconfigured state:
ros2 service call /lc_demo/change_state lifecycle_msgs/srv/ChangeState "{transition: {id: 2}}"

from typing import Optional
import rclpy
from rclpy.lifecycle import LifecycleNode
from rclpy.lifecycle import LifecyclePublisher
from rclpy.lifecycle import LifecycleState
from rclpy.lifecycle import TransitionCallbackReturn
from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy
from rclpy.timer import Timer

from std_msgs.msg import Bool

class LifecycleSubDemo(LifecycleNode):
  
  def __init__(self, node_name, **kwargs):
    super().__init__(node_name, **kwargs)

    self._count: int = 0
    self._pub: Optional[LifecyclePublisher] = None
    self._timer: Optional[Timer] = None

  def publish(self):
    self._pub.publish(Bool(data=False))
  

  def on_configure(self, state: LifecycleState) -> TransitionCallbackReturn:
    self._pub = self.create_lifecycle_publisher(Bool, "/test", 1)
    self._timer = self.create_timer(1.0, self.publish, autostart=False)
    return TransitionCallbackReturn.SUCCESS

  def on_activate(self, state: LifecycleState) -> TransitionCallbackReturn:
    # publisher automatically activated by parent class transition method
    r = super().on_activate(state)
    self._timer.reset()
    return r
  
  def on_deactivate(self, state: LifecycleState) -> TransitionCallbackReturn:
    self._timer.cancel()
    return super().on_deactivate(state)

  def on_cleanup(self, state: LifecycleState) -> TransitionCallbackReturn:
    self.destroy_timer(self._timer)
    self.destroy_publisher(self._pub)
    return TransitionCallbackReturn.SUCCESS
  
  def on_error(self, state: LifecycleState) -> TransitionCallbackReturn:
    self.get_logger().error("on_error triggered")
    return TransitionCallbackReturn.SUCCESS


def main():
    rclpy.init()
    lc_demo_node = LifecycleSubDemo('lc_demo')
    rclpy.spin(lc_demo_node)

    #while rclpy.ok():
    #  lc_demo_node = LifecycleSubDemo('lc_demo')
    #  try:
    #    rclpy.spin(lc_demo_node)
    #  except rclpy._rclpy_pybind11.RCLError:
    #    pass

    rclpy.shutdown()

if __name__ == '__main__':
  main()

Expected behavior

The node enters the error processing state, triggering the on_error callback.

Actual behavior

An exception is thrown and the node exits:
rclpy._rclpy_pybind11.RCLError: Failed to trigger lifecycle state machine transition: Transition is not registered., at ./src/rcl_lifecycle.c:355

Additional information

The commented-out section in main shows how this exception can be caught. However, I don't want the node to exit at all. What if I have a complex state built up and then an external program makes a bad service call? I should be able to process the error within the node (give a failure response to the service caller) and continue on.

@mjforan
Copy link
Author

mjforan commented Jan 5, 2024

@ivanpauno

@chrisbitter
Copy link

Just encountered the same behavior and agree that a wrong service call should not break the node but fail the service request.

I would even argue that the expected behavior should not even trigger the error processing transition. The request should just be ignored.

I achieved this behavior by modifying LifecycleNodeMixin.__on_change_state

    def __on_change_state(
        self,
        req: lifecycle_msgs.srv.ChangeState.Request,
        resp: lifecycle_msgs.srv.ChangeState.Response
    ):
        self.__check_is_initialized()
        transition_id = req.transition.id

        # modification
        available_transition_ids = [t[0] for t in self._state_machine.available_transitions]
                
        if transition_id not in available_transition_ids:
              self.get_logger().warn(f"Invalid transition {transition_id}")
              resp.success = False
              return resp
        # modification end
        ....

@Barry-Xu-2018
Copy link
Contributor

@chrisbitter Do you plan to submit a PR to fix this issue?

chrisbitter added a commit to chrisbitter/rclpy that referenced this issue Jul 22, 2024
Signed-off-by: Christian Bitter <cbi@circuli-ion.com>
@chrisbitter
Copy link

@Barry-Xu-2018 done: #1317

@fujitatomoya
Copy link
Collaborator

  • rclcpp lifecycle talker
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run lifecycle lifecycle_talker 
[WARN] [1721684923.724041941] [rcl_lifecycle]: No transition matching 2 found for current state unconfigured
[ERROR] [1721684923.724117548] [lc_talker]: Unable to start transition 2 from current state unconfigured: Transition is not registered., at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl_lifecycle/src/rcl_lifecycle.c:355
[WARN] [1721684994.830895033] [rcl_lifecycle]: No transition matching 2 found for current state unconfigured
[ERROR] [1721684994.830930978] [lc_talker]: Unable to start transition 2 from current state unconfigured: Transition is not registered., at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl_lifecycle/src/rcl_lifecycle.c:355

root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 service call /lc_talker/change_state lifecycle_msgs/srv/ChangeState "{transition: {id: 2}}"
requester: making request: lifecycle_msgs.srv.ChangeState_Request(transition=lifecycle_msgs.msg.Transition(id=2, label=''))

response:
lifecycle_msgs.srv.ChangeState_Response(success=False)

I believe this is correct behavior.
Since this is error transition for the state machine, detects error, and stays in the current state.

  • rclpy lifecycle talker
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run lifecycle_py lifecycle_talker 
[WARN] [1721684828.072130783] [rcl_lifecycle]: No transition matching 2 found for current state unconfigured
Traceback (most recent call last):
  File "/root/ros2_ws/colcon_ws/install/lifecycle_py/lib/lifecycle_py/lifecycle_talker", line 33, in <module>
    sys.exit(load_entry_point('lifecycle-py', 'console_scripts', 'lifecycle_talker')())
             ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
  File "/root/ros2_ws/colcon_ws/build/lifecycle_py/lifecycle_py/talker.py", line 151, in main
    executor.spin()
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 308, in spin
    self.spin_once()
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 827, in spin_once
    self._spin_once_impl(timeout_sec)
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 822, in _spin_once_impl
    raise handler.exception()
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/task.py", line 239, in __call__
    self._handler.send(None)
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 508, in handler
    await call_coroutine()
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 447, in _execute
    response = await await_or_execute(srv.callback, request, srv.srv_type.Response())
               ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/executors.py", line 111, in await_or_execute
    return callback(*args)
           ^^^^^^^^^^^^^^^
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/lifecycle/node.py", line 359, in __on_change_state
    cb_return_code = self.__change_state(transition_id)
                     ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
  File "/root/ros2_ws/colcon_ws/install/rclpy/lib/python3.12/site-packages/rclpy/lifecycle/node.py", line 326, in __change_state
    self._state_machine.trigger_transition_by_id(transition_id, True)
rclpy._rclpy_pybind11.RCLError: Failed to trigger lifecycle state machine transition: Transition is not registered., at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl_lifecycle/src/rcl_lifecycle.c:355
[ros2run]: Process exited with failure 1

the problem is, response never comes back.

root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 service call /lc_talker/change_state lifecycle_msgs/srv/ChangeState "{transition: {id: 2}}"
requester: making request: lifecycle_msgs.srv.ChangeState_Request(transition=lifecycle_msgs.msg.Transition(id=2, label=''))

...

this is unexpected behavior...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants