Tutorial Ros2Supervisor Import your Urdf Robot - cyberbotics/webots_ros2 GitHub Wiki

⚠️THE SUPPORT FOR URDF AND XACRO SPAWNER IS DEPRECATED! IT WILL BE REMOVED IN VERSION 2024.0.0.⚠️

With the Ros2Supervisor node it is now possible to spawn robots based on your URDF files!

Note: The import feature is based on this conversion tool.

Set up

In order to be able to easily import your URDF file into a simulation, several changes have to be done in the standard launch file.

The URDFSpawner process

First of all, a request has to be sent to the Ros2Supervisor node in order to spawn the robot. This done with the URDFSpawner process.

Here is the possible arguments, in addition to the ones proposed by ExecuteProcess:

  • name (string): Set the name of the robot in the simulation. It is required and has to be unique in the simulation.
  • urdf_path (string): Set the path to the URDF file to convert. Has to be specified if robot_description is not specified.
  • robot_description (string): Set the content of a URDF file to convert. Has to be specified if urdf_path is not specified.
  • translation (string): Set the position of the robot when it will be spawned in the simulation.
  • rotation (string): Set the rotation of the robot when it will be spawned in the simulation.
  • normal (bool): If set, the normals are exported if present in the URDF definition. Default is False.
  • box_collision (bool): If set, the bounding objects are approximated using boxes. Default is False.
  • init_pos (string): Set the initial positions of your robot joints. Example: init_pos='[1.2, 0.5, -1.5]' would set the first 3 joints of your robot to the specified values, and leave the rest with their default value.
  • relative_path_prefix (string): If robot_description is used, the relative paths in your URDF file will use this prefix. Example: filename='head.obj' with relative_path_prefix='/home/user/myRobot/' will become filename='/home/user/myRobot/head.obj'.

The synchronization with the webots_ros2_driver node

Then the webots_ros2_driver node has to be started only when the URDF robot has be spawned. This is done by adding an event_handler on the URDFSpawner process and specify the webots_ros2_driver node in the get_webots_driver_node() function. This will permit to start the node only when the robot has been successfully spawned. In case you need to start some other nodes with the webots_ros2_driver node, you can specify a list of nodes for the second argument of the get_webots_driver_node() function.

Launch file template

Here is a simple template on how to write such a launch file:

import os
import pathlib
import launch
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.substitutions.path_join_substitution import PathJoinSubstitution
from launch_ros.actions import Node
from webots_ros2_driver.urdf_spawner import URDFSpawner, get_webots_driver_node
from webots_ros2_driver.webots_launcher import WebotsLauncher

def generate_launch_description():
    world = LaunchConfiguration('world')
    package_dir = get_package_share_directory("my_package")
    urdf_path = os.path.join(package_dir, 'resource', 'my_urdf_file.urdf')
    robot_description = pathlib.Path(urdf_path).read_text()

    # Define your URDF robots here
    # The name of an URDF robot has to match the WEBOTS_CONTROLLER_URL of the driver node
    # You can specify the URDF file to use with "urdf_path"
    spawn_URDF_robot = URDFSpawner(
        name='myRobot',
        urdf_path=urdf_path,
        translation='0 0 1',
        rotation='0 0 1 -1.5708',
    )

    # Driver nodes
    # When having multiple robot it is enough to specify the `additional_env` argument.
    # The `WEBOTS_CONTROLLER_URL` has to match the robot name in the world file.
    # You can check for more information at:
    # https://cyberbotics.com/doc/guide/running-extern-robot-controllers#single-simulation-and-multiple-extern-robot-controllers
    robot_driver = Node(
        package='webots_ros2_driver',
        executable='driver',
        output='screen',
        additional_env={'WEBOTS_CONTROLLER_URL': 'myRobot'},
        parameters=[
            {'robot_description': robot_description},
        ],
    )

    # The WebotsLauncher is a Webots custom action that allows you to start a Webots simulation instance.
    # It searches for the Webots installation in the path specified by the `WEBOTS_HOME` environment variable and default installation paths.
    # The Ros2Supervisor node is mandatory to spawn an URDF robot.
    # The accepted arguments are:
    # - `world` (str): Path to the world to launch.
    # - `gui` (bool): Whether to display GUI or not.
    # - `mode` (str): Can be `pause`, `realtime`, or `fast`.
    # - `ros2_supervisor` (bool): Spawn the `Ros2Supervisor` custom node that communicates with a Supervisor robot in the simulation.
    webots = WebotsLauncher(
        world=PathJoinSubstitution([package_dir, 'worlds', world]),
        ros2_supervisor=True
    )

    return LaunchDescription([
        DeclareLaunchArgument(
            'world',
            default_value='robotic_arms.wbt',
            description='Choose one of the world files from `/webots_ros2_universal_robot/worlds` directory'
        ),
        # Starts Webots
        webots,

        # Starts the Ros2Supervisor node created with the WebotsLauncher
        webots._supervisor,

        # Request the spawn of your URDF robot
        spawn_URDF_robot,

        # Launch the driver node once the URDF robot is spawned
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessIO(
                target_action=spawn_URDF_robot,
                on_stdout=lambda event: get_webots_driver_node(event, robot_driver),
            )
        ),

        # This action will kill all nodes once the Webots simulation has exited
        launch.actions.RegisterEventHandler(
            event_handler=launch.event_handlers.OnProcessExit(
                target_action=webots,
                on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
            )
        )
    ])

Example

An example of launch file can be found here.

This launch file is the one used for the Multirobot example from Universal Robots. The example might appear complex at first sight, but it is simply a combination of the spawn feature and the reset feature.

You can test this launch file as it is shipped with the webots_ros2_universal_robot package by running the following in a terminal:

ros2 launch webots_ros2_universal_robot multirobot_launch.py

Xacro file

In case you want to use directly a Xacro file rather than a URDF file, all you need is to replace:

urdf_path = os.path.join(package_dir, 'resource', 'my_urdf_file.urdf')
robot_description = pathlib.Path(urdf_path).read_text()

spawn_URDF_robot = URDFSpawner(
    name='myRobot',
    urdf_path=urdf_path,
)

by the following (relative_path_prefix has to be the folder where your Xacro file is):

xacro_path = os.path.join(package_dir, 'resource', 'my_xacro_file.xacro')
robot_description = xacro.process_file(xacro_path).toxml()

spawn_URDF_ur5e = URDFSpawner(
    name='myRobot',
    robot_description=robot_description,
    relative_path_prefix=os.path.join(package_dir, 'resource'),
)