|
| 1 | +Setting up a Reset Handler |
| 2 | +========================== |
| 3 | + |
| 4 | +**Goal:** Extend a robot simulation with a reset handler to restart nodes when the reset button of Webots is pressed. |
| 5 | + |
| 6 | +**Tutorial level:** Advanced |
| 7 | + |
| 8 | +**Time:** 10 minutes |
| 9 | + |
| 10 | +.. contents:: Contents |
| 11 | + :depth: 2 |
| 12 | + :local: |
| 13 | + |
| 14 | +Background |
| 15 | +---------- |
| 16 | + |
| 17 | +In this tutorial, you will learn how to implement a reset handler in a robot simulation using Webots. |
| 18 | +The Webots reset button reverts the world to the initial state and restarts controllers. |
| 19 | +It is convenient as it quickly resets the simulation, but in the context of ROS 2, robot controllers are not started again making the simulation stop. |
| 20 | +The reset handler allows you to restart specific nodes or perform additional actions when the reset button in Webots is pressed. |
| 21 | +This can be useful for scenarios where you need to reset the state of your simulation or restart specific components without completely restarting the complete ROS system. |
| 22 | + |
| 23 | +Prerequisites |
| 24 | +------------- |
| 25 | + |
| 26 | +Before proceeding with this tutorial, make sure you have completed the following: |
| 27 | + |
| 28 | +- Understanding of ROS 2 nodes and topics covered in the beginner :doc:`../../../../Tutorials`. |
| 29 | +- Knowledge of Webots and ROS 2 and its interface package. |
| 30 | +- Familiarity with :doc:`./Setting-Up-Simulation-Webots-Basic`. |
| 31 | + |
| 32 | + |
| 33 | +Reset Handler for Simple Cases (Controllers Only) |
| 34 | +------------------------------------------------- |
| 35 | + |
| 36 | +In the launch file of your package, add the ``respawn`` parameter. |
| 37 | + |
| 38 | +.. code-block:: python |
| 39 | +
|
| 40 | + def generate_launch_description(): |
| 41 | + robot_driver = WebotsController( |
| 42 | + robot_name='my_robot', |
| 43 | + parameters=[ |
| 44 | + {'robot_description': robot_description_path} |
| 45 | + ], |
| 46 | +
|
| 47 | + # Every time one resets the simulation the controller is automatically respawned |
| 48 | + respawn=True |
| 49 | + ) |
| 50 | +
|
| 51 | + # Starts Webots |
| 52 | + webots = WebotsLauncher(world=PathJoinSubstitution([package_dir, 'worlds', world])) |
| 53 | +
|
| 54 | + return LaunchDescription([ |
| 55 | + webots, |
| 56 | + robot_driver |
| 57 | + ]) |
| 58 | +
|
| 59 | +On reset, Webots kills all driver nodes. |
| 60 | +Therefore, to start them again after reset, you should set the ``respawn`` property of the driver node to ``True``. |
| 61 | +It will ensure driver nodes are up and running after the reset. |
| 62 | + |
| 63 | +Reset Handler for Multiple Nodes (No Shutdown Required) |
| 64 | +------------------------------------------------------- |
| 65 | + |
| 66 | +If you have some other nodes that have to be started along with the driver node (e.g. ``ros2_control`` nodes), then you can use the ``OnProcessExit`` event handler: |
| 67 | + |
| 68 | +.. code-block:: python |
| 69 | +
|
| 70 | + def get_ros2_control_spawners(*args): |
| 71 | + # Declare here all nodes that must be restarted at simulation reset |
| 72 | + ros_control_node = Node( |
| 73 | + package='controller_manager', |
| 74 | + executable='spawner', |
| 75 | + arguments=['diffdrive_controller'] |
| 76 | + ) |
| 77 | + return [ |
| 78 | + ros_control_node |
| 79 | + ] |
| 80 | +
|
| 81 | + def generate_launch_description(): |
| 82 | + robot_driver = WebotsController( |
| 83 | + robot_name='my_robot', |
| 84 | + parameters=[ |
| 85 | + {'robot_description': robot_description_path} |
| 86 | + ], |
| 87 | +
|
| 88 | + # Every time one resets the simulation the controller is automatically respawned |
| 89 | + respawn=True |
| 90 | + ) |
| 91 | +
|
| 92 | + # Starts Webots |
| 93 | + webots = WebotsLauncher(world=PathJoinSubstitution([package_dir, 'worlds', world])) |
| 94 | +
|
| 95 | + # Declare the reset handler that respawns nodes when robot_driver exits |
| 96 | + reset_handler = launch.actions.RegisterEventHandler( |
| 97 | + event_handler=launch.event_handlers.OnProcessExit( |
| 98 | + target_action=robot_driver, |
| 99 | + on_exit=get_ros2_control_spawners, |
| 100 | + ) |
| 101 | + ) |
| 102 | +
|
| 103 | + return LaunchDescription([ |
| 104 | + webots, |
| 105 | + robot_driver, |
| 106 | + reset_handler |
| 107 | + ] + get_ros2_control_spawners()) |
| 108 | +
|
| 109 | +It is not possible to use the ``respawn`` property on the ``ros2_control`` node, as the spawner exits during launch time and not when the simulation is reset. |
| 110 | +Instead we should declare a list of nodes in a function (e.g. ``get_ros2_control_spawners``). |
| 111 | +The nodes of this list are started along other nodes when executing the launch file. |
| 112 | +With the ``reset_handler``, the function is also declared as action to start when the ``robot_driver`` node exits, which corresponds to the moment when the simulation is reset in the Webots interface. |
| 113 | +The ``robot_driver`` node still has the ``respawn`` property set to ``True``, so that it gets restarted along with ``ros2_control`` nodes. |
| 114 | + |
| 115 | +Reset Handler Requiring Node Shutdown |
| 116 | +------------------------------------- |
| 117 | + |
| 118 | +With the current ROS 2 launch API, there is no way to make the reset work in launch files where nodes need to be shutdown before the restart (e.g. ``Nav2`` or ``RViz``). |
| 119 | +The reason is that currently, ROS 2 doesn't allow to shutdown specific nodes from a launch file. |
| 120 | +There is a solution, but it requires to manually restart nodes after pushing the reset button. |
| 121 | + |
| 122 | +Webots needs to be started in a specific launch file without other nodes. |
| 123 | + |
| 124 | +.. code-block:: python |
| 125 | +
|
| 126 | + def generate_launch_description(): |
| 127 | + # Starts Webots |
| 128 | + webots = WebotsLauncher(world=PathJoinSubstitution([package_dir, 'worlds', world])) |
| 129 | +
|
| 130 | + return LaunchDescription([ |
| 131 | + webots |
| 132 | + ]) |
| 133 | +
|
| 134 | +
|
| 135 | +A second launch file must be started from another process. |
| 136 | +This launch file contains all other nodes, including robot controllers/plugins, Navigation2 nodes, RViz, state publishers, etc. |
| 137 | + |
| 138 | +.. code-block:: python |
| 139 | +
|
| 140 | + def generate_launch_description(): |
| 141 | + robot_driver = WebotsController( |
| 142 | + robot_name='my_robot', |
| 143 | + parameters=[ |
| 144 | + {'robot_description': robot_description_path} |
| 145 | + ] |
| 146 | + ) |
| 147 | +
|
| 148 | + ros_control_node = Node( |
| 149 | + package='controller_manager', |
| 150 | + executable='spawner', |
| 151 | + arguments=['diffdrive_controller'] |
| 152 | + ) |
| 153 | +
|
| 154 | + nav2_node = IncludeLaunchDescription( |
| 155 | + PythonLaunchDescriptionSource(os.path.join( |
| 156 | + get_package_share_directory('nav2_bringup'), 'launch', 'bringup_launch.py')), |
| 157 | + launch_arguments=[ |
| 158 | + ('map', nav2_map), |
| 159 | + ('params_file', nav2_params), |
| 160 | + ], |
| 161 | + ) |
| 162 | +
|
| 163 | + rviz = Node( |
| 164 | + package='rviz2', |
| 165 | + executable='rviz2', |
| 166 | + output='screen' |
| 167 | + ) |
| 168 | +
|
| 169 | + # Declare the handler that shuts all nodes down when robot_driver exits |
| 170 | + shutdown_handler = launch.actions.RegisterEventHandler( |
| 171 | + event_handler=launch.event_handlers.OnProcessExit( |
| 172 | + target_action=robot_driver, |
| 173 | + on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())], |
| 174 | + ) |
| 175 | + ) |
| 176 | +
|
| 177 | + return LaunchDescription([ |
| 178 | + robot_driver, |
| 179 | + ros_control_node, |
| 180 | + nav2_node, |
| 181 | + rviz, |
| 182 | + shutdown_handler |
| 183 | + ]) |
| 184 | +
|
| 185 | +The second launch file contains a handler that triggers a shutdown event when the driver node exits (which is the case when the simulation is reset). |
| 186 | +This second launch file must be manually restarted from the command line after pressing the reset button. |
| 187 | + |
| 188 | +Summary |
| 189 | +------- |
| 190 | + |
| 191 | +In this tutorial, you learned how to implement a reset handler in a robot simulation using Webots. |
| 192 | +The reset handler allows you to restart specific nodes or perform additional actions when the reset button in Webots is pressed. |
| 193 | +You explored different approaches based on the complexity of your simulation and the requirements of your nodes. |
0 commit comments