-
-
Notifications
You must be signed in to change notification settings - Fork 164
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 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_core.webots_launcher import WebotsLauncher
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 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.
# Typically, we provide it the `robot_description` parameters from a URDF file and `ros2_control_params` from the `ros2_control` configuration file.
webots_robot_driver = Node(
package='webots_ros2_driver',
executable='driver',
parameters=[
{'robot_description': robot_description},
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 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.
- 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