diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md
index 157d4cb5..c13819d6 100644
--- a/ros_gz_sim_demos/README.md
+++ b/ros_gz_sim_demos/README.md
@@ -126,7 +126,7 @@ Publishes IMU readings.
Publishes magnetic field readings.
- ros2 launch ros_gz_sim_demos magnetometer.launch.py
+ ros2 launch ros_gz_sim_demos magnetometer.launch.xml
![](images/magnetometer_demo.png)
@@ -208,6 +208,6 @@ and transforms of a robot in rviz.
To try the demo launch:
- ros2 launch ros_gz_sim_demos tf_bridge.launch.py
+ ros2 launch ros_gz_sim_demos tf_bridge.launch.xml
![](images/tf_bridge.gif)
diff --git a/ros_gz_sim_demos/config/magnetometer.yaml b/ros_gz_sim_demos/config/magnetometer.yaml
new file mode 100644
index 00000000..e5d38d2e
--- /dev/null
+++ b/ros_gz_sim_demos/config/magnetometer.yaml
@@ -0,0 +1,6 @@
+# Magnetometer configuration.
+- topic_name: "/magnetometer"
+ ros_type_name: "sensor_msgs/msg/MagneticField"
+ gz_type_name: "gz.msgs.Magnetometer"
+ lazy: true
+ direction: GZ_TO_ROS
diff --git a/ros_gz_sim_demos/config/tf_bridge.yaml b/ros_gz_sim_demos/config/tf_bridge.yaml
new file mode 100644
index 00000000..9debbf11
--- /dev/null
+++ b/ros_gz_sim_demos/config/tf_bridge.yaml
@@ -0,0 +1,14 @@
+# tf_bridge configuration.
+- ros_topic_name: "/joint_states"
+ gz_topic_name: "/world/default/model/double_pendulum_with_base0/joint_state"
+ ros_type_name: "sensor_msgs/msg/JointState"
+ gz_type_name: "gz.msgs.Model"
+ lazy: true
+ direction: GZ_TO_ROS
+
+- ros_topic_name: "/tf"
+ gz_topic_name: "/model/double_pendulum_with_base0/pose"
+ ros_type_name: "tf2_msgs/msg/TFMessage"
+ gz_type_name: "gz.msgs.Pose_V"
+ lazy: true
+ direction: GZ_TO_ROS
diff --git a/ros_gz_sim_demos/launch/magnetometer.launch.py b/ros_gz_sim_demos/launch/magnetometer.launch.py
deleted file mode 100644
index e35b8487..00000000
--- a/ros_gz_sim_demos/launch/magnetometer.launch.py
+++ /dev/null
@@ -1,63 +0,0 @@
-# Copyright 2019 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument
-from launch.actions import IncludeLaunchDescription
-from launch.conditions import IfCondition
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch.substitutions import LaunchConfiguration
-
-from launch_ros.actions import Node
-
-
-def generate_launch_description():
-
- pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')
-
- gz_sim = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')),
- launch_arguments={
- 'gz_args': '-r sensors.sdf'
- }.items(),
- )
-
- # RQt
- rqt = Node(
- package='rqt_topic',
- executable='rqt_topic',
- arguments=['-t'],
- condition=IfCondition(LaunchConfiguration('rqt'))
- )
-
- # Bridge
- bridge = Node(
- package='ros_gz_bridge',
- executable='parameter_bridge',
- arguments=['/magnetometer@sensor_msgs/msg/MagneticField@gz.msgs.Magnetometer'],
- output='screen'
- )
-
- return LaunchDescription([
- gz_sim,
- DeclareLaunchArgument('rqt', default_value='true',
- description='Open RQt.'),
- bridge,
- rqt
- ])
diff --git a/ros_gz_sim_demos/launch/magnetometer.launch.xml b/ros_gz_sim_demos/launch/magnetometer.launch.xml
new file mode 100644
index 00000000..10639b43
--- /dev/null
+++ b/ros_gz_sim_demos/launch/magnetometer.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.py b/ros_gz_sim_demos/launch/tf_bridge.launch.py
deleted file mode 100644
index 42f76cdc..00000000
--- a/ros_gz_sim_demos/launch/tf_bridge.launch.py
+++ /dev/null
@@ -1,59 +0,0 @@
-# Copyright 2022 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription
-from launch.actions import ExecuteProcess
-from launch_ros.actions import Node
-
-
-def generate_launch_description():
- pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos')
- return LaunchDescription([
- # Launch gazebo
- ExecuteProcess(
- cmd=[
- 'gz', 'sim', '-r',
- os.path.join(
- pkg_ros_gz_sim_demos,
- 'models',
- 'double_pendulum_model.sdf'
- )
- ]
- ),
- # Launch a bridge to forward tf and joint states to ros2
- Node(
- package='ros_gz_bridge',
- executable='parameter_bridge',
- arguments=[
- '/world/default/model/double_pendulum_with_base0/joint_state@'
- 'sensor_msgs/msg/JointState[gz.msgs.Model',
- '/model/double_pendulum_with_base0/pose@'
- 'tf2_msgs/msg/TFMessage[gz.msgs.Pose_V'
- ],
- remappings=[
- ('/model/double_pendulum_with_base0/pose', '/tf'),
- ('/world/default/model/double_pendulum_with_base0/joint_state', '/joint_states')
- ]
- ),
- # Launch rviz
- Node(
- package='rviz2',
- executable='rviz2',
- arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')]
- )
- ])
diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.xml b/ros_gz_sim_demos/launch/tf_bridge.launch.xml
new file mode 100644
index 00000000..321a3d8c
--- /dev/null
+++ b/ros_gz_sim_demos/launch/tf_bridge.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+