Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -205,10 +205,24 @@ The code file will also tell ``tf2`` how to place the whole model using the ``t
^^^^^^^^^^^^^^^^^^^^^^

Create a new ``urdf_tutorial_cpp/launch`` folder.
Open your editor and paste the following code, saving it as ``urdf_tutorial_cpp/launch/launch.py``
Open your editor and paste the following code, saving it as ``urdf_tutorial_cpp/launch/launch`` with the extension ``.py``, ``.xml``, or ``.yaml``

.. literalinclude:: launch/launch.py
:language: python
.. tabs::

.. group-tab:: Python

.. literalinclude:: launch/launch.py
:language: python

.. group-tab:: XML

.. literalinclude:: launch/launch.xml
:language: xml

.. group-tab:: YAML

.. literalinclude:: launch/launch.yaml
:language: yaml


5 Edit the CMakeLists.txt file
Expand Down Expand Up @@ -298,7 +312,7 @@ Source the setup files:
7 View the results
^^^^^^^^^^^^^^^^^^

To launch your new package run the following command:
To launch your new package run the following command (using ``launch`` with extension ``.py``, ``.xml``, or ``.yaml``):

.. code-block:: console

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -203,10 +203,24 @@ Fire up your favorite editor and paste the following code into ``second_ros2_ws/
^^^^^^^^^^^^^^^^^^^^^^

Create a new ``second_ros2_ws/src/urdf_tutorial_r2d2/launch`` folder.
Open your editor and paste the following code, saving it as ``second_ros2_ws/src/urdf_tutorial_r2d2/launch/demo_launch.py``
Open your editor and paste the following code, saving it as ``second_ros2_ws/src/urdf_tutorial_r2d2/launch/demo_launch`` with the extension ``.py``, ``.xml``, or ``.yaml``

.. literalinclude:: launch/demo_launch.py
:language: python
.. tabs::

.. group-tab:: Python

.. literalinclude:: launch/demo_launch.py
:language: python

.. group-tab:: XML

.. literalinclude:: launch/demo_launch.xml
:language: xml

.. group-tab:: YAML

.. literalinclude:: launch/demo_launch.yaml
:language: yaml


5 Edit the setup.py file
Expand Down Expand Up @@ -278,7 +292,7 @@ Source the setup files:
7 View the results
^^^^^^^^^^^^^^^^^^

Launch the package
Launch the package (using ``demo_launch`` with extension ``.py``, ``.xml``, or ``.yaml``)

.. code-block:: console

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,23 +43,61 @@ However, it does take time to generate, so be aware that your launch file might

To run xacro within your launch file, you need to put the ``Command`` substitution as a parameter to the ``robot_state_publisher``.

.. code-block:: python

path_to_urdf = get_package_share_path('turtlebot3_description') / 'urdf' / 'turtlebot3_burger.urdf'
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{
'robot_description': ParameterValue(
Command(['xacro ', str(path_to_urdf)]), value_type=str
)
}]
)
.. tabs::

.. group-tab:: Python

.. code-block:: python

path_to_urdf = get_package_share_path('turtlebot3_description') / 'urdf' / 'turtlebot3_burger.urdf'
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{
'robot_description': ParameterValue(
Command(['xacro ', str(path_to_urdf)]), value_type=str
)
}]
)

.. group-tab:: XML

.. code-block:: xml

<node pkg="robot_state_publisher" exec="robot_state_publisher" name="robot_state_publisher">
<param name="robot_description" value="$(command 'xacro $(find-pkg-share turtlebot3_description)/urdf/turtlebot3_burger.urdf')" />
</node>

.. group-tab:: YAML

.. code-block:: yaml

- node:
pkg: "robot_state_publisher"
exec: "robot_state_publisher"
name: "robot_state_publisher"
param:
- name: "robot_description"
value: "$(command 'xacro $(find-pkg-share turtlebot3_description)/urdf/turtlebot3_burger.urdf')"

An easier way to load the robot model is to use the `urdf_launch <https://github.com/ros/urdf_launch>`_ package to automatically load the xacro/urdf.

.. literalinclude:: launch/urdf_display_launch.py
:language: python
.. tabs::

.. group-tab:: Python

.. literalinclude:: launch/urdf_display_launch.py
:language: python

.. group-tab:: XML

.. literalinclude:: launch/urdf_display_launch.xml
:language: xml

.. group-tab:: YAML

.. literalinclude:: launch/urdf_display_launch.yaml
:language: yaml

At the top of the URDF file, you must specify a namespace in order for the file to parse properly.
For example, these are the first two lines of a valid xacro file:
Expand Down
13 changes: 13 additions & 0 deletions source/Tutorials/Intermediate/URDF/launch/demo_launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- 'use_sim_time' is used to have ros2 use /clock topic for the time source -->
<arg name="use_sim_time" default="false" description="Use simulation (Gazebo) clock if true" />

<node pkg="robot_state_publisher" exec="robot_state_publisher" name="robot_state_publisher" output="screen" args="$(file-content $(find-pkg-share urdf_tutorial_r2d2)/r2d2.urdf.xml)">
<param name="use_sim_time" value="$(var use_sim_time)" />
<param name="robot_description" value="$(file-content $(find-pkg-share urdf_tutorial_r2d2)/r2d2.urdf.xml)" />
</node>

<node pkg="urdf_tutorial_r2d2" exec="state_publisher" name="state_publisher" output="screen" />
</launch>

27 changes: 27 additions & 0 deletions source/Tutorials/Intermediate/URDF/launch/demo_launch.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
%YAML 1.2
---
launch:
# 'use_sim_time' is used to have ros2 use /clock topic for the time source
- arg:
name: "use_sim_time"
default: "false"
description: "Use simulation (Gazebo) clock if true"

- node:
pkg: "robot_state_publisher"
exec: "robot_state_publisher"
name: "robot_state_publisher"
output: "screen"
args: "$(file-content $(find-pkg-share urdf_tutorial_r2d2)/r2d2.urdf.xml)"
param:
- name: "use_sim_time"
value: "$(var use_sim_time)"
- name: "robot_description"
value: "$(file-content $(find-pkg-share urdf_tutorial_r2d2)/r2d2.urdf.xml)"

- node:
pkg: "urdf_tutorial_r2d2"
exec: "state_publisher"
name: "state_publisher"
output: "screen"

13 changes: 13 additions & 0 deletions source/Tutorials/Intermediate/URDF/launch/launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- 'use_sim_time' is used to have ros2 use /clock topic for the time source -->
<arg name="use_sim_time" default="false" description="Use simulation (Gazebo) clock if true" />

<node pkg="robot_state_publisher" exec="robot_state_publisher" name="robot_state_publisher" output="screen" args="$(file-content $(find-pkg-share urdf_tutorial_cpp)/urdf/r2d2.urdf.xml)">
<param name="use_sim_time" value="$(var use_sim_time)" />
<param name="robot_description" value="$(file-content $(find-pkg-share urdf_tutorial_cpp)/urdf/r2d2.urdf.xml)" />
</node>

<node pkg="urdf_tutorial_cpp" exec="urdf_tutorial_cpp" name="urdf_tutorial_cpp" output="screen" />
</launch>

27 changes: 27 additions & 0 deletions source/Tutorials/Intermediate/URDF/launch/launch.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
%YAML 1.2
---
launch:
# 'use_sim_time' is used to have ros2 use /clock topic for the time source
- arg:
name: "use_sim_time"
default: "false"
description: "Use simulation (Gazebo) clock if true"

- node:
pkg: "robot_state_publisher"
exec: "robot_state_publisher"
name: "robot_state_publisher"
output: "screen"
args: "$(file-content $(find-pkg-share urdf_tutorial_cpp)/urdf/r2d2.urdf.xml)"
param:
- name: "use_sim_time"
value: "$(var use_sim_time)"
- name: "robot_description"
value: "$(file-content $(find-pkg-share urdf_tutorial_cpp)/urdf/r2d2.urdf.xml)"

- node:
pkg: "urdf_tutorial_cpp"
exec: "urdf_tutorial_cpp"
name: "urdf_tutorial_cpp"
output: "screen"

Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<include file="$(find-pkg-share urdf_launch)/launch/display.launch.py">
<arg name="urdf_package" value="turtlebot3_description" />
<arg name="urdf_package_path" value="urdf/turtlebot3_burger.urdf" />
</include>
</launch>

11 changes: 11 additions & 0 deletions source/Tutorials/Intermediate/URDF/launch/urdf_display_launch.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
%YAML 1.2
---
launch:
- include:
file: "$(find-pkg-share urdf_launch)/launch/display.launch.py"
arg:
- name: "urdf_package"
value: "turtlebot3_description"
- name: "urdf_package_path"
value: "urdf/turtlebot3_burger.urdf"