-
-
Notifications
You must be signed in to change notification settings - Fork 157
Tutorial Creating a Custom Package
Since webots_ros2
1.1.0 the package includes the webots_ros2_driver
. The main objectives of the sub-package are:
- It automatically creates a ROS 2 interface out of a Webots robot model.
- It allows users to configure the ROS 2 interface in URDF files.
- It allows users to extend the interface using the
pluginlib
plugin mechanism.
In this tutorial, we will emphasize the main elements needed to create a ROS 2 custom package (with a Webots simulation) by utilizing the webots_ros2_driver
features.
We recommend the following project structure when creating a custom ROS 2 package with a Webots simulation:
.
├── launch
│ └── robot_launch.py
├── resource
│ ├── webots_robot_description.urdf
│ └── ros2_control_configuration.yml
├── worlds
└── webots_world_file.wbt
├── webots_ros2_package_example
│ └── __init__.py
├── package.xml
└── setup.py
Your ROS 2 package may have more files (or even less), but these files are the most relevant for the typical Webots ROS 2 simulations.
- The
launch/robot_launch.py
file contains ROS 2 launch instructions (see the Launch File section). - The
resource/webots_robot_description.urdf
file contains ROS 2 interface configuration (see the URDF<webots>
Tag section). - The
resource/ros2_control_configuration.yml
file containsros2_control
configuration. - The
worlds/webots_world_file.wbt
file contains the Webots world description. The file is typically created in the Webots world editor.
An example of a Webots ROS 2 interface configuration file (webots_robot_description.urdf
) is provided below:
<?xml version="1.0" ?>
<robot name="RobotName">
<webots>
<!-- Whole Webots-related configuration is placed under the <webots> tag -->
<!-- For almost all Webots devices a ROS 2 interface will be created automatically. -->
<!-- If a ROS 2 interface for a device is not explicitly configured (e.g. update rate, topic name, and frame name) then configuration will be assumed. -->
<!-- The ROS 2 interface configuration is specified within a <device> tag. -->
<!-- * The `reference` attribute matches the Webots device `name` parameter. -->
<!-- * The configuration under the <ros> tag is a ROS 2 specific device configuration. -->
<device reference="LDS-01">
<ros>
<topicName>/scan</topicName>
</ros>
</device>
<!-- The `webots_ros2_driver` package creates a ROS 2 interface for most devices available in Webots. -->
<!-- However, if there is no adequate Webots ROS 2 interface then you can create a custom plugin. -->
<!-- The `webots_ros2` package already comes with a few predefined plugins that you can use as an example. -->
<!-- For example, the IMU combines Webots InertialUnit, Gyro, and Accelerometer. -->
<!-- When using a plugin it is necessary to specify the type attribute in the <plugin> tag. -->
<!-- The tag matches the type attribute in the <class> tag defined by the pluginlib. -->
<plugin type="webots_ros2_driver::Ros2IMU">
<frameName>imu_link</frameName>
<inertialUnitName>inertial_unit</inertialUnitName>
<gyroName>gyro</gyroName>
<accelerometerName>accelerometer</accelerometerName>
</plugin>
<!-- The ros2_control implementation is provided as another out-of-the-box plugin. -->
<plugin type="webots_ros2_control::Ros2Control" />
</webots>
<!-- Other URDF tags can freely coexist with the <webots> tag in the same URDF file. -->
<ros2_control name="WebotsControl" type="system">
<hardware>
<!-- When using Webots ros2_control implementation it is necessary to specify the following line in the ros2_control configuration. -->
<plugin>webots_ros2_control::Ros2ControlSystem</plugin>
</hardware>
<joint name="right wheel motor">
<state_interface name="position"/>
<command_interface name="velocity"/>
</joint>
<joint name="left wheel motor">
<state_interface name="position"/>
<command_interface name="velocity"/>
</joint>
</ros2_control>
</robot>
In the following launch file, we provide an explanation of the most often used elements in Webots ROS 2 simulations:
import os
import pathlib
import launch
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_launcher import Ros2SupervisorLauncher
def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_turtlebot')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'webots_robot_description.urdf')).read_text()
ros2_control_params = os.path.join(package_dir, 'resource', 'ros2_control_configuration.yml')
# 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 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`.
webots = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'webots_world_file.wbt')
)
# The Ros2Supervisor node is a special node interacting with the simulation.
# For example, it publishes the /clock topic of the simulation or permits to spawn robot from URDF files.
# By default, the respawn option is set to True.
ros2_supervisor = Ros2SupervisorLauncher()
# The node which interacts with a robot in the Webots simulation is located in the `webots_ros2_driver` package under name `driver`.
# It is necessary to run such a node for each robot in the simulation.
# The `WEBOTS_CONTROLLER_URL` variable has to match the robot name in the world file.
# Typically, we can provide it the `robot_description` parameters from a URDF file in order to configure the interface, `set_robot_state_publisher` in order to let the node give the URDF generated from Webots to the `robot_state_publisher` and `ros2_control_params` from the `ros2_control` configuration file.
webots_robot_driver = Node(
package='webots_ros2_driver',
executable='driver',
additional_env={'WEBOTS_CONTROLLER_URL': 'robot'},
parameters=[
{'robot_description': robot_description,
'set_robot_state_publisher': True},
ros2_control_params
],
)
# Often we want to publish robot transforms, so we use the `robot_state_publisher` node for that.
# If robot model is not specified in the URDF file then Webots can help us with the URDF exportation feature.
# Since the exportation feature is available only once the simulation has started and the `robot_state_publisher` node requires a `robot_description` parameter before we have to specify a dummy robot.
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{
'robot_description': '<robot name=""><link name=""/></robot>'
}],
)
# Standard ROS 2 launch description
return launch.LaunchDescription([
# Start the Webots node
webots,
# Start the Ros2Supervisor node
ros2_supervisor,
# Start the Webots robot driver
webots_robot_driver,
# Start the robot_state_publisher
robot_state_publisher,
# 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())],
)
)
])
Your simulation may be more or less complex depending on the simulations you are running. However, the provided launch file depicts the most often used launch elements in Webots simulations.
It might happen that you want to parametrize how Webots is launched with the WebotsLauncher
process or parametrize the Ros2Supervisor
and webots_ros2_driver
nodes.
Here is a list of all arguments you can use with some further explanations on this process and these nodes.
Most of the arguments of the WebotsLauncher
will start Webots with different command line arguments.
You can find below the list of arguments of WebotsLauncher
and their impact on the command line arguments:
-
gui
(bool): IfFalse
, set the--no-rendering
,--stdout
,--stderr
and--minimize
flags. Default isTrue
. -
mode
(string): Set the--mode
flag with the same value. Default is'realtime'
. -
stream
(bool): IfTrue
, set the--stream
flag. Default isFalse
.
The world
argument specify the path to the world to be used, it can be a literal string or a Substitution, like in the Examples of this repository.
output
(by default set to 'screen'
) and extra arguments will be used by the init
function of launch.actions.ExecuteProcess.
The Ros2Supervisor
node can be easily started in launch files with the Ros2SupervisorLauncher
class.
The Ros2SupervisorLauncher process is simply an extra layer on the Node class from launch_ros, setting the required arguments to launch the Ros2Supervisor
node and setting by default respawn
to True
and output
to 'screen'
.
Note: As for every external controller of Webots, this node has to define an environment variable
WEBOTS_ROBOT_NAME
equal to the name of the robot that will be controlled by the node. The name of the robot isRos2Supervisor
, therefore no other robot can have this name.More information can be found on the
Ros2Supervisor
node here.
The webots_ros2_driver
node is launched as a standard node, thus there is not particular argument.
However there are two important parts.
The first one is to set an environment variable WEBOTS_CONTROLLER_URL
equal to the name of the robot in the simulation with the additional_env
argument. No doing this or writing a wrong name will prevent the webots_ros2_driver
node from connecting to the robot.
The second part allows other parameters to be defined. Beside the standard 'use_sim_time': True
that can be used or a configuration file .yml
, the two following parameters can be used:
-
robot_description
(string): If set, thewebots_ros2_driver
node will parse the string to configure the ROS 2 interface. For example, this include using plugins (premade or custom ones), activating by default or renaming some topics. -
set_robot_state_publisher
(bool): IfTrue
, therobot_description
parameter of a (potentially existing)robot_state_publisher
node will be overridden by the content of a URDF file generated by Webots based on the robot in the simulation. This URDF may be not as complete as a URDF made by yourself. Default isFalse
.
A tutorial on how to create a custom Webots - ROS 2 simulation can be found on the official ROS 2 documentation. It also include an example on how to extend the interface with a Python plugin.
- The Ros2Supervisor Node
- Using URDF or Xacro
- Import your URDF Robot in Webots
- Refresh or Add URDF a Robot in a Running Simulation
- Wheeled robots
- Robotic arms
- Automobiles
- Drones