Skip to content

/assisted_teleop action client persists after node has been destroyed  #4696

@tiwaojo

Description

@tiwaojo

Bug report

Required Info:

Steps to reproduce issue

  • Setup your workspace

    mkdir -p ros2_ws/src
    cd ros2_ws/src
    ros2 pkg create --build-type ament_python --license Apache-2.0 --node-name my_node my_package
  • Install dependencies

    Add the following to `dep.repos`
    repositories:
    src/nav2_simple_commander:
        type: git
        url: https://github.com/SteveMacenski/navigation2-release.git
        version: release/humble/nav2_simple_commander
    src/nav2_common:
        type: git
        url: https://github.com/SteveMacenski/navigation2-release.git
        version: release/humble/nav2_common
    src/nav2_msgs:
        type: git
        url: https://github.com/SteveMacenski/navigation2-release.git
        version: release/humble/nav2_msgs
    touch src/dep.repos
    vcs import --skip-existing --input src/dep.repos
    pip3 install fastapi uvicorn
  • Duplicate the action_client_interfaces package from the action_tutorials repo into your workspace.

  • Configure the package.xml file of your package to depend on the action_client_interfaces package by adding the following line:

        <?xml version="1.0"?>
        ...
    +   <depend>violation_reporter_interfaces</depend>
        ...
  • Create the action client node by adding the following code to /ros2_ws/src/my_package/my_package/my_node.py

    /ros2_ws/src/my_package/my_package/my_node.py
    from nav2_simple_commander.robot_navigator import BasicNavigator
    import rclpy
    from rclpy.action import ActionClient
    
    from action_tutorials_interfaces.action import Fibonacci
    
    class MinimalActionClient(BasicNavigator):
    
        def __init__(self):
            super().__init__('fibonacci_action_client')
            self._action_client = ActionClient(self, Fibonacci, 'fibonacci')
    
        def send_goal(self, order):
            goal_msg = Fibonacci.Goal()
            goal_msg.order = order
    
            self._action_client.wait_for_server()
    
            return self._action_client.send_goal_async(goal_msg)
    
        def destroy_node(self):
            self._action_client.destroy()
            # self.assisted_teleop_client.destroy() # uncomment to fix. parent class(BasicNavigator) should be responsible for deleting this action client
            super().destroy_node()
    
    def main(args=None):
        rclpy.init(args=args)
    
        action_client = MinimalActionClient()
    
        future = action_client.send_goal(10)
    
        rclpy.spin_until_future_complete(action_client, future)
        
        action_client.destroy_node()
    
    
    if __name__ == '__main__':
        main()
      ```
    
    </details>
  • Create your api by adding the following code to /ros2_ws/src/my_package/api/main.py

    /ros2_ws/src/my_package/api/main.py
    import uvicorn
    from fastapi import FastAPI, Request, Response
    from fastapi.middleware.cors import CORSMiddleware
    import rclpy
    from rclpy.executors import SingleThreadedExecutor
    from rclpy.task import Future
    from my_package.my_node import MinimalActionClient
    from contextlib import asynccontextmanager
    
    
    @asynccontextmanager
    async def lifespan(app: FastAPI):
        # Perform startup actions here
        print("Starting up...")
        print("Initializing ROS Context...")
        rclpy.init(args=None)
    
        yield
    
        # Perform cleanup actions here
        print("Tearing down...")
        print("Shutting down ROS Context...")
        rclpy.try_shutdown()
    
    
    app = FastAPI(
        lifespan=lifespan,
        responses={200: {"description": "Success"}, 404: {"description": "Not found"}},
    )
    
    origins = ["*"]
    
    app.add_middleware(
        CORSMiddleware,
        allow_origins=origins,
        allow_credentials=True,
        allow_methods=["*"],
        allow_headers=["*"],
    )
    
    
    @app.get(
        path="/",
        name="index",
        tags=["home"],
        summary="Home page",
    )
    async def index(request: Request, response: Response):
        return {"message": "Hello World"}
    
    
    @app.get(path="/example_endpoint")
    async def example_endpoint(request: Request, response: Response):
        executor = SingleThreadedExecutor()
        action_client_node = MinimalActionClient()
        try:
            if rclpy.ok():
                # future: Future = action_client_node.send_goal(order=10)
    
                action_client_node.get_logger().info("Goal sent. Waiting for result...")
                # rclpy.spin_until_future_complete(action_client_node,future=future)
                executor.add_node(action_client_node)
                # executor.spin_once_until_future_complete(future=future,timeout_sec=20)
    
        except Exception as e:
            action_client_node.get_logger().error(f"An error occurred: {e}")
        finally:
            action_client_node.get_logger().info("Destroying client node")
            action_client_node.destroy_node()
            executor.remove_node(action_client_node)
            executor.shutdown()
    
    
    def main(args=None):
        try:
            uvicorn.run(
                app=app,
                host="127.0.0.1",
                port=8000,
            )
        except KeyboardInterrupt:
            print("Shutting down server...")
    
    
    if __name__ == "__main__":
        main()
  • Build the workspace

    colcon build --symlink-install
  • Run the program

    source install/setup.bash
    python3 src/my_package/api/main.py
    # or 
    uvicorn src.my_package.api.main:app
  • Send a request to the server

    curl http://127.0.0.1:8000/example_endpoint
  • List nodes

    ros2 node list

Expected behavior

All nodes, actions and callbacks should be destroyed when the request is completed.

Actual behavior

The action client node is not destroyed when the server is shut down. As the /assisted_teleop action client is not destroyed, the node is not destroyed. This can be seen by running ros2 action list after the request has been served. Any further calls to the same endpoint recreates the action client node and the action client, hereby creating duplicate nodes and actions.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions