diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md
index 10d8ddd5..e9346e0b 100644
--- a/ros_gz_sim_demos/README.md
+++ b/ros_gz_sim_demos/README.md
@@ -134,7 +134,12 @@ Publishes magnetic field readings.
Publishes satellite navigation readings, only available in Fortress on.
- ros2 launch ros_gz_sim_demos navsat.launch.py
+GNSS information can be obtained as:
+
+ # sensor_msgs/msg/NavSatFix
+ ros2 launch ros_gz_sim_demos navsat.launch.xml
+ # gps_msgs/msg/GPSFix
+ ros2 launch ros_gz_sim_demos navsat_gpsfix.launch.xml
![](images/navsat_demo.png)
diff --git a/ros_gz_sim_demos/config/navsat.yaml b/ros_gz_sim_demos/config/navsat.yaml
new file mode 100644
index 00000000..0a68ab80
--- /dev/null
+++ b/ros_gz_sim_demos/config/navsat.yaml
@@ -0,0 +1,6 @@
+# Navsat configuration.
+- topic_name: "/navsat"
+ ros_type_name: "sensor_msgs/msg/NavSatFix"
+ gz_type_name: "gz.msgs.NavSat"
+ lazy: true
+ direction: GZ_TO_ROS
diff --git a/ros_gz_sim_demos/config/navsat_gpsfix.yaml b/ros_gz_sim_demos/config/navsat_gpsfix.yaml
new file mode 100644
index 00000000..07784eee
--- /dev/null
+++ b/ros_gz_sim_demos/config/navsat_gpsfix.yaml
@@ -0,0 +1,6 @@
+# Navsat_gpsfix configuration.
+- topic_name: "/navsat"
+ ros_type_name: "gps_msgs/msg/GPSFix"
+ gz_type_name: "gz.msgs.NavSat"
+ lazy: true
+ direction: GZ_TO_ROS
diff --git a/ros_gz_sim_demos/launch/navsat.launch.py b/ros_gz_sim_demos/launch/navsat.launch.py
deleted file mode 100644
index f2172f93..00000000
--- a/ros_gz_sim_demos/launch/navsat.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': '-v 4 -r spherical_coordinates.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=['/navsat@sensor_msgs/msg/NavSatFix@gz.msgs.NavSat'],
- output='screen'
- )
-
- return LaunchDescription([
- gz_sim,
- DeclareLaunchArgument('rqt', default_value='true',
- description='Open RQt.'),
- bridge,
- rqt
- ])
diff --git a/ros_gz_sim_demos/launch/navsat.launch.xml b/ros_gz_sim_demos/launch/navsat.launch.xml
new file mode 100644
index 00000000..97ad0adc
--- /dev/null
+++ b/ros_gz_sim_demos/launch/navsat.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
diff --git a/ros_gz_sim_demos/launch/navsat_gpsfix.launch.py b/ros_gz_sim_demos/launch/navsat_gpsfix.launch.py
deleted file mode 100644
index 83adcdcc..00000000
--- a/ros_gz_sim_demos/launch/navsat_gpsfix.launch.py
+++ /dev/null
@@ -1,63 +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 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': '-v 4 -r spherical_coordinates.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=['/navsat@gps_msgs/msg/GPSFix@gz.msgs.NavSat'],
- output='screen'
- )
-
- return LaunchDescription([
- gz_sim,
- DeclareLaunchArgument('rqt', default_value='true',
- description='Open RQt.'),
- bridge,
- rqt
- ])
diff --git a/ros_gz_sim_demos/launch/navsat_gpsfix.launch.xml b/ros_gz_sim_demos/launch/navsat_gpsfix.launch.xml
new file mode 100644
index 00000000..10c8c8a4
--- /dev/null
+++ b/ros_gz_sim_demos/launch/navsat_gpsfix.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+