Skip to content

Commit

Permalink
Update launch files to declare WebotsController node (#11) (#3763)
Browse files Browse the repository at this point in the history
* change launch files

* Update Setting-Up-Simulation-Webots-Basic.rst

* update minimal version tutorial 2

* add upcoming versions
  • Loading branch information
ygoumaz authored Jun 30, 2023
1 parent 687cd01 commit b7d9cb2
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 31 deletions.
15 changes: 5 additions & 10 deletions source/Tutorials/Advanced/Simulators/Webots/Code/robot_launch.py
Original file line number Diff line number Diff line change
@@ -1,28 +1,23 @@
import os
import pathlib
import launch
from launch_ros.actions import Node
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.utils import controller_url_prefix
from webots_ros2_driver.webots_controller import WebotsController


def generate_launch_description():
package_dir = get_package_share_directory('my_package')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'my_robot.urdf')).read_text()
robot_description_path = os.path.join(package_dir, 'resource', 'my_robot.urdf')

webots = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)

my_robot_driver = Node(
package='webots_ros2_driver',
executable='driver',
output='screen',
additional_env={'WEBOTS_CONTROLLER_URL': controller_url_prefix() + 'my_robot'},
my_robot_driver = WebotsController(
robot_name='my_robot',
parameters=[
{'robot_description': robot_description},
{'robot_description': robot_description_path},
]
)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,28 +1,24 @@
import os
import pathlib
import launch
from launch_ros.actions import Node
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
from webots_ros2_driver.webots_launcher import WebotsLauncher, Ros2SupervisorLauncher
from webots_ros2_driver.utils import controller_url_prefix
from webots_ros2_driver.webots_launcher import WebotsLauncher
from webots_ros2_driver.webots_controller import WebotsController


def generate_launch_description():
package_dir = get_package_share_directory('my_package')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'my_robot.urdf')).read_text()
robot_description_path = os.path.join(package_dir, 'resource', 'my_robot.urdf')

webots = WebotsLauncher(
world=os.path.join(package_dir, 'worlds', 'my_world.wbt')
)

my_robot_driver = Node(
package='webots_ros2_driver',
executable='driver',
output='screen',
additional_env={'WEBOTS_CONTROLLER_URL': controller_url_prefix() + 'my_robot'},
my_robot_driver = WebotsController(
robot_name='my_robot',
parameters=[
{'robot_description': robot_description},
{'robot_description': robot_description_path},
]
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ Prerequisites
This is a continuation of the first part of the tutorial: :doc:`./Setting-Up-Simulation-Webots-Basic`.
It is mandatory to start with the first part to set up the custom packages and necessary files.

This tutorial is compatible with version 2023.1.0 of ``webots_ros2`` and Webots R2023b, as well as upcoming versions.

Tasks
-----

Expand Down Expand Up @@ -153,7 +155,7 @@ Go to the file ``robot_launch.py`` and replace ``def generate_launch_description

.. literalinclude:: Code/robot_launch_sensor.py
:language: python
:lines: 11-44
:lines: 10-40

This will create an ``obstacle_avoider`` node that will be included in the ``LaunchDescription``.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ In particular, :doc:`../../../Beginner-CLI-Tools/Introducing-Turtlesim/Introduci
The Linux and ROS commands of this tutorial must be run in a pre-configured Linux Virtual Machine (VM).
The following page :doc:`./Installation-MacOS` explains how to install the ``webots_ros2`` package on macOS.

This tutorial is compatible with version 2023.1.0 of ``webots_ros2`` and Webots R2023b, as well as upcoming versions.

Tasks
-----

Expand Down Expand Up @@ -344,10 +346,10 @@ You have to specify in the constructor which world file the simulator will open.
.. literalinclude:: Code/robot_launch.py
:language: python
:dedent: 4
:lines: 15-17
:lines: 13-15

Then, the ROS node interacting with the simulated robot is created.
This node, named ``driver``, is located in the ``webots_ros2_driver`` package.
This node, named ``WebotsController``, is located in the ``webots_ros2_driver`` package.

.. tabs::

Expand All @@ -366,33 +368,32 @@ This node, named ``driver``, is located in the ``webots_ros2_driver`` package.

In your case, you need to run a single instance of this node, because you have a single robot in the simulation.
But if you had more robots in the simulation, you would have to run one instance of this node per robot.
``WEBOTS_CONTROLLER_URL`` is used to define the name of the robot the driver should connect to.
The ``controller_url_prefix()`` method is mandatory, as it allows ``webots_ros2_driver`` to add the correct protocol prefix depending on your platform.
The ``robot_description`` parameter holds the contents of the URDF file which refers to the ``MyRobotDriver`` plugin.
You can see the ``driver`` node as the interface that connects your controller plugin to the target robot.
The ``robot_name`` parameter is used to define the name of the robot the driver should connect to.
The ``robot_description`` parameter holds the path to the URDF file which refers to the ``MyRobotDriver`` plugin.
You can see the ``WebotsController`` node as the interface that connects your controller plugin to the target robot.

.. literalinclude:: Code/robot_launch.py
:language: python
:dedent: 4
:lines: 19-27
:lines: 17-22

After that, the two nodes are set to be launched in the ``LaunchDescription`` constructor:

.. literalinclude:: Code/robot_launch.py
:language: python
:dedent: 4
:lines: 29-31
:lines: 24-26

Finally, an optional part is added in order to shutdown all the nodes once Webots terminates (e.g., when it gets closed from the graphical user interface).

.. literalinclude:: Code/robot_launch.py
:language: python
:dedent: 8
:lines: 32-37
:lines: 27-32

.. note::

More details on ``webots_ros2_driver`` and ``WebotsLauncher`` arguments can be found `on the nodes reference page <https://github.com/cyberbotics/webots_ros2/wiki/References-Nodes>`_.
More details on ``WebotsController`` and ``WebotsLauncher`` arguments can be found `on the nodes reference page <https://github.com/cyberbotics/webots_ros2/wiki/References-Nodes>`_.

6 Edit additional files
^^^^^^^^^^^^^^^^^^^^^^^
Expand Down

0 comments on commit b7d9cb2

Please sign in to comment.