From 77379e977587ca6942d976117ef93e08236fed93 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 11:34:52 -0400
Subject: [PATCH 01/29] Begin renaming ignition -> gz, updating dependencies
 for Jazzy

---
 .github/workflows/ci.yml                      |   6 +-
 README.md                                     |   4 +-
 .../CHANGELOG.rst                             |   2 +-
 .../CMakeLists.txt                            |   4 +-
 turtlebot4_gz_bringup/README.md               |   1 +
 .../config/turtlebot4_node.yaml               |   0
 .../gui/lite/gui.config                       |   0
 .../gui/standard/gui.config                   |   0
 .../launch/gazebo.launch.py                   |  59 +++++++++---------
 .../launch/ros_gz_bridge.launch.py            |   0
 .../launch/turtlebot4_gazebo.launch.py        |   8 +--
 .../launch/turtlebot4_nodes.launch.py         |  14 ++---
 .../launch/turtlebot4_spawn.launch.py         |  14 ++---
 .../package.xml                               |  12 ++--
 .../worlds/depot.sdf                          |   0
 .../worlds/maze.sdf                           |   0
 .../worlds/warehouse.sdf                      |   0
 .../CHANGELOG.rst                             |   0
 .../CMakeLists.txt                            |   2 +-
 turtlebot4_gz_gui_plugins/README.md           |   1 +
 .../Turtlebot4Hmi/CMakeLists.txt              |   0
 .../Turtlebot4Hmi/Turtlebot4Hmi.cc            |   0
 .../Turtlebot4Hmi/Turtlebot4Hmi.config        |   0
 .../Turtlebot4Hmi/Turtlebot4Hmi.hh            |   0
 .../Turtlebot4Hmi/Turtlebot4Hmi.qml           |   0
 .../Turtlebot4Hmi/Turtlebot4Hmi.qrc           |   0
 .../Turtlebot4Hmi/images/One Dot.png          | Bin
 .../Turtlebot4Hmi/images/Power.png            | Bin
 .../Turtlebot4Hmi/images/Two Dots.png         | Bin
 .../package.xml                               |   2 +-
 .../CHANGELOG.rst                             |   0
 .../CMakeLists.txt                            |   4 +-
 .../turtlebot4_gz_toolbox}/hmi_node.hpp       |  10 +--
 .../package.xml                               |   6 +-
 .../src/hmi_main.cpp                          |   4 +-
 .../src/hmi_node.cpp                          |   4 +-
 turtlebot4_ignition_bringup/README.md         |   1 -
 turtlebot4_ignition_gui_plugins/README.md     |   1 -
 turtlebot4_simulator/package.xml              |   8 +--
 39 files changed, 84 insertions(+), 83 deletions(-)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/CHANGELOG.rst (96%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/CMakeLists.txt (84%)
 create mode 100644 turtlebot4_gz_bringup/README.md
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/config/turtlebot4_node.yaml (100%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/gui/lite/gui.config (100%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/gui/standard/gui.config (100%)
 rename turtlebot4_ignition_bringup/launch/ignition.launch.py => turtlebot4_gz_bringup/launch/gazebo.launch.py (65%)
 rename turtlebot4_ignition_bringup/launch/ros_ign_bridge.launch.py => turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py (100%)
 rename turtlebot4_ignition_bringup/launch/turtlebot4_ignition.launch.py => turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py (91%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/launch/turtlebot4_nodes.launch.py (83%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/launch/turtlebot4_spawn.launch.py (96%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/package.xml (83%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/worlds/depot.sdf (100%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/worlds/maze.sdf (100%)
 rename {turtlebot4_ignition_bringup => turtlebot4_gz_bringup}/worlds/warehouse.sdf (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/CHANGELOG.rst (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/CMakeLists.txt (92%)
 create mode 100644 turtlebot4_gz_gui_plugins/README.md
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/CMakeLists.txt (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/Turtlebot4Hmi.cc (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/Turtlebot4Hmi.config (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/Turtlebot4Hmi.hh (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/Turtlebot4Hmi.qml (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/Turtlebot4Hmi.qrc (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/images/One Dot.png (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/images/Power.png (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/Turtlebot4Hmi/images/Two Dots.png (100%)
 rename {turtlebot4_ignition_gui_plugins => turtlebot4_gz_gui_plugins}/package.xml (93%)
 rename {turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox}/CHANGELOG.rst (100%)
 rename {turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox}/CMakeLists.txt (94%)
 rename {turtlebot4_ignition_toolbox/include/turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox/include/turtlebot4_gz_toolbox}/hmi_node.hpp (87%)
 rename {turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox}/package.xml (83%)
 rename {turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox}/src/hmi_main.cpp (86%)
 rename {turtlebot4_ignition_toolbox => turtlebot4_gz_toolbox}/src/hmi_node.cpp (96%)
 delete mode 100644 turtlebot4_ignition_bringup/README.md
 delete mode 100644 turtlebot4_ignition_gui_plugins/README.md

diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index 0667be7..b2a431b 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -17,6 +17,6 @@ jobs:
           target-ros2-distro: humble
           import-token: ${{ secrets.GITHUB_TOKEN }}
           package-name:
-            turtlebot4_ignition_bringup
-            turtlebot4_ignition_gui_plugins
-            turtlebot4_ignition_toolbox
+            turtlebot4_gz_bringup
+            turtlebot4_gz_gui_plugins
+            turtlebot4_gz_toolbox
diff --git a/README.md b/README.md
index 0d1812e..1e07c14 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
 # Turtlebot4 Simulator
 
-Turtlebot4 Simulation using Ignition Gazebo.
+Turtlebot4 Simulation using Harmonic Gazebo for ROS 2 Jazzy.
 
 Visit the [TurtleBot 4 User Manual](https://turtlebot.github.io/turtlebot4-user-manual/software/turtlebot4_simulator.html) for details.
 
@@ -10,5 +10,5 @@ sudo apt-get update && sudo apt-get install wget
 sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
 wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
 sudo apt-get update
-sudo apt-get install ignition-fortress ros-humble-turtlebot4-simulator
+sudo apt-get install gz-harmonic ros-jazzy-turtlebot4-simulator
 ```
diff --git a/turtlebot4_ignition_bringup/CHANGELOG.rst b/turtlebot4_gz_bringup/CHANGELOG.rst
similarity index 96%
rename from turtlebot4_ignition_bringup/CHANGELOG.rst
rename to turtlebot4_gz_bringup/CHANGELOG.rst
index f394e88..b64f965 100644
--- a/turtlebot4_ignition_bringup/CHANGELOG.rst
+++ b/turtlebot4_gz_bringup/CHANGELOG.rst
@@ -1,5 +1,5 @@
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package turtlebot4_ignition_bringup
+Changelog for package turtlebot4_gz_bringup
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
 1.0.2 (2024-04-15)
diff --git a/turtlebot4_ignition_bringup/CMakeLists.txt b/turtlebot4_gz_bringup/CMakeLists.txt
similarity index 84%
rename from turtlebot4_ignition_bringup/CMakeLists.txt
rename to turtlebot4_gz_bringup/CMakeLists.txt
index 031251d..05e9151 100644
--- a/turtlebot4_ignition_bringup/CMakeLists.txt
+++ b/turtlebot4_gz_bringup/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 3.8)
-project(turtlebot4_ignition_bringup)
+project(turtlebot4_gz_bringup)
 
 if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
   add_compile_options(-Wall -Wextra -Wpedantic)
@@ -8,7 +8,7 @@ endif()
 # find dependencies
 find_package(ament_cmake REQUIRED)
 
-find_package(ros_ign_interfaces REQUIRED)
+find_package(ros_gz_interfaces REQUIRED)
 
 install(
   DIRECTORY config gui launch worlds
diff --git a/turtlebot4_gz_bringup/README.md b/turtlebot4_gz_bringup/README.md
new file mode 100644
index 0000000..8a77b14
--- /dev/null
+++ b/turtlebot4_gz_bringup/README.md
@@ -0,0 +1 @@
+# turtlebot4_gz_bringup
diff --git a/turtlebot4_ignition_bringup/config/turtlebot4_node.yaml b/turtlebot4_gz_bringup/config/turtlebot4_node.yaml
similarity index 100%
rename from turtlebot4_ignition_bringup/config/turtlebot4_node.yaml
rename to turtlebot4_gz_bringup/config/turtlebot4_node.yaml
diff --git a/turtlebot4_ignition_bringup/gui/lite/gui.config b/turtlebot4_gz_bringup/gui/lite/gui.config
similarity index 100%
rename from turtlebot4_ignition_bringup/gui/lite/gui.config
rename to turtlebot4_gz_bringup/gui/lite/gui.config
diff --git a/turtlebot4_ignition_bringup/gui/standard/gui.config b/turtlebot4_gz_bringup/gui/standard/gui.config
similarity index 100%
rename from turtlebot4_ignition_bringup/gui/standard/gui.config
rename to turtlebot4_gz_bringup/gui/standard/gui.config
diff --git a/turtlebot4_ignition_bringup/launch/ignition.launch.py b/turtlebot4_gz_bringup/launch/gazebo.launch.py
similarity index 65%
rename from turtlebot4_ignition_bringup/launch/ignition.launch.py
rename to turtlebot4_gz_bringup/launch/gazebo.launch.py
index 58b3c60..9672e6a 100644
--- a/turtlebot4_ignition_bringup/launch/ignition.launch.py
+++ b/turtlebot4_gz_bringup/launch/gazebo.launch.py
@@ -33,7 +33,7 @@
                           choices=['true', 'false'],
                           description='use_sim_time'),
     DeclareLaunchArgument('world', default_value='warehouse',
-                          description='Ignition World'),
+                          description='Simulation World'),
     DeclareLaunchArgument('model', default_value='lite',
                           choices=['standard', 'lite'],
                           description='Turtlebot4 Model'),
@@ -43,10 +43,10 @@
 def generate_launch_description():
 
     # Directories
-    pkg_turtlebot4_ignition_bringup = get_package_share_directory(
-        'turtlebot4_ignition_bringup')
-    pkg_turtlebot4_ignition_gui_plugins = get_package_share_directory(
-        'turtlebot4_ignition_gui_plugins')
+    pkg_turtlebot4_gz_bringup = get_package_share_directory(
+        'turtlebot4_gz_bringup')
+    pkg_turtlebot4_gz_gui_plugins = get_package_share_directory(
+        'turtlebot4_gz_gui_plugins')
     pkg_turtlebot4_description = get_package_share_directory(
         'turtlebot4_description')
     pkg_irobot_create_description = get_package_share_directory(
@@ -55,38 +55,38 @@ def generate_launch_description():
         'irobot_create_ignition_bringup')
     pkg_irobot_create_ignition_plugins = get_package_share_directory(
         'irobot_create_ignition_plugins')
-    pkg_ros_ign_gazebo = get_package_share_directory(
-        'ros_ign_gazebo')
+    pkg_ros_gz_sim = get_package_share_directory(
+        'ros_gz_sim')
 
     # Set ignition resource path
-    ign_resource_path = SetEnvironmentVariable(
-        name='IGN_GAZEBO_RESOURCE_PATH',
+    gz_resource_path = SetEnvironmentVariable(
+        name='GZ_GAZEBO_RESOURCE_PATH',
         value=[
-            os.path.join(pkg_turtlebot4_ignition_bringup, 'worlds'), ':' +
+            os.path.join(pkg_turtlebot4_gz_bringup, 'worlds'), ':' +
             os.path.join(pkg_irobot_create_ignition_bringup, 'worlds'), ':' +
             str(Path(pkg_turtlebot4_description).parent.resolve()), ':' +
             str(Path(pkg_irobot_create_description).parent.resolve())])
 
-    ign_gui_plugin_path = SetEnvironmentVariable(
-        name='IGN_GUI_PLUGIN_PATH',
+    gz_gui_plugin_path = SetEnvironmentVariable(
+        name='GZ_GUI_PLUGIN_PATH',
         value=[
-            os.path.join(pkg_turtlebot4_ignition_gui_plugins, 'lib'), ':' +
+            os.path.join(pkg_turtlebot4_gz_gui_plugins, 'lib'), ':' +
             os.path.join(pkg_irobot_create_ignition_plugins, 'lib')])
 
     # Paths
-    ign_gazebo_launch = PathJoinSubstitution(
-        [pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py'])
+    gz_sim_launch = PathJoinSubstitution(
+        [pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'])
 
     # Ignition gazebo
-    ignition_gazebo = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource([ign_gazebo_launch]),
+    gazebo = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource([gz_sim_launch]),
         launch_arguments=[
-            ('ign_args', [LaunchConfiguration('world'),
+            ('gz_args', [LaunchConfiguration('world'),
                           '.sdf',
                           ' -v 4',
                           ' --gui-config ',
                           PathJoinSubstitution(
-                            [pkg_turtlebot4_ignition_bringup,
+                            [pkg_turtlebot4_gz_bringup,
                              'gui',
                              LaunchConfiguration('model'),
                              'gui.config'])])
@@ -94,17 +94,18 @@ def generate_launch_description():
     )
 
     # Clock bridge
-    clock_bridge = Node(package='ros_gz_bridge', executable='parameter_bridge',
-                        name='clock_bridge',
-                        output='screen',
-                        arguments=[
-                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock'
-                        ])
+    # TODO No longer needed in Jazzy?
+#    clock_bridge = Node(package='ros_gz_bridge', executable='parameter_bridge',
+#                        name='clock_bridge',
+#                        output='screen',
+#                        arguments=[
+#                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock'
+#                        ])
 
     # Create launch description and add actions
     ld = LaunchDescription(ARGUMENTS)
-    ld.add_action(ign_resource_path)
-    ld.add_action(ign_gui_plugin_path)
-    ld.add_action(ignition_gazebo)
-    ld.add_action(clock_bridge)
+    ld.add_action(gz_resource_path)
+    ld.add_action(gz_gui_plugin_path)
+    ld.add_action(gazebo)
+#    ld.add_action(clock_bridge)
     return ld
diff --git a/turtlebot4_ignition_bringup/launch/ros_ign_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
similarity index 100%
rename from turtlebot4_ignition_bringup/launch/ros_ign_bridge.launch.py
rename to turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
diff --git a/turtlebot4_ignition_bringup/launch/turtlebot4_ignition.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
similarity index 91%
rename from turtlebot4_ignition_bringup/launch/turtlebot4_ignition.launch.py
rename to turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
index 107a14e..90dbfd1 100644
--- a/turtlebot4_ignition_bringup/launch/turtlebot4_ignition.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
@@ -42,14 +42,14 @@
 
 def generate_launch_description():
     # Directories
-    pkg_turtlebot4_ignition_bringup = get_package_share_directory(
-        'turtlebot4_ignition_bringup')
+    pkg_turtlebot4_gz_bringup = get_package_share_directory(
+        'turtlebot4_gz_bringup')
 
     # Paths
     ignition_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_ignition_bringup, 'launch', 'ignition.launch.py'])
+        [pkg_turtlebot4_gz_bringup, 'launch', 'gazebo.launch.py'])
     robot_spawn_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_ignition_bringup, 'launch', 'turtlebot4_spawn.launch.py'])
+        [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_spawn.launch.py'])
 
     ignition = IncludeLaunchDescription(
         PythonLaunchDescriptionSource([ignition_launch]),
diff --git a/turtlebot4_ignition_bringup/launch/turtlebot4_nodes.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
similarity index 83%
rename from turtlebot4_ignition_bringup/launch/turtlebot4_nodes.launch.py
rename to turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
index 2d7b89e..19eca96 100644
--- a/turtlebot4_ignition_bringup/launch/turtlebot4_nodes.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
@@ -32,13 +32,13 @@
 def generate_launch_description():
 
     # Directories
-    pkg_turtlebot4_ignition_bringup = get_package_share_directory('turtlebot4_ignition_bringup')
+    pkg_turtlebot4_gz_bringup = get_package_share_directory('turtlebot4_gz_bringup')
 
     # Parameters
     param_file_cmd = DeclareLaunchArgument(
         'param_file',
         default_value=PathJoinSubstitution(
-            [pkg_turtlebot4_ignition_bringup, 'config', 'turtlebot4_node.yaml']),
+            [pkg_turtlebot4_gz_bringup, 'config', 'turtlebot4_node.yaml']),
         description='Turtlebot4 Robot param file'
     )
 
@@ -55,10 +55,10 @@ def generate_launch_description():
     )
 
     # Turtlebot4 Ignition Hmi node
-    turtlebot4_ignition_hmi_node = Node(
-        package='turtlebot4_ignition_toolbox',
-        name='turtlebot4_ignition_hmi_node',
-        executable='turtlebot4_ignition_hmi_node',
+    turtlebot4_gz_hmi_node = Node(
+        package='turtlebot4_gz_toolbox',
+        name='turtlebot4_gz_hmi_node',
+        executable='turtlebot4_gz_hmi_node',
         output='screen',
         condition=LaunchConfigurationEquals('model', 'standard')
     )
@@ -67,5 +67,5 @@ def generate_launch_description():
     ld = LaunchDescription(ARGUMENTS)
     ld.add_action(param_file_cmd)
     ld.add_action(turtlebot4_node)
-    ld.add_action(turtlebot4_ignition_hmi_node)
+    ld.add_action(turtlebot4_gz_hmi_node)
     return ld
diff --git a/turtlebot4_ignition_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
similarity index 96%
rename from turtlebot4_ignition_bringup/launch/turtlebot4_spawn.launch.py
rename to turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index de381ea..34df9d0 100644
--- a/turtlebot4_ignition_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -60,8 +60,8 @@
 def generate_launch_description():
 
     # Directories
-    pkg_turtlebot4_ignition_bringup = get_package_share_directory(
-        'turtlebot4_ignition_bringup')
+    pkg_turtlebot4_gz_bringup = get_package_share_directory(
+        'turtlebot4_gz_bringup')
     pkg_turtlebot4_description = get_package_share_directory(
         'turtlebot4_description')
     pkg_turtlebot4_viz = get_package_share_directory(
@@ -75,11 +75,11 @@ def generate_launch_description():
 
     # Paths
     turtlebot4_ros_ign_bridge_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_ignition_bringup, 'launch', 'ros_ign_bridge.launch.py'])
+        [pkg_turtlebot4_gz_bringup, 'launch', 'ros_ign_bridge.launch.py'])
     rviz_launch = PathJoinSubstitution(
         [pkg_turtlebot4_viz, 'launch', 'view_robot.launch.py'])
     turtlebot4_node_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_ignition_bringup, 'launch', 'turtlebot4_nodes.launch.py'])
+        [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_nodes.launch.py'])
     create3_nodes_launch = PathJoinSubstitution(
         [pkg_irobot_create_common_bringup, 'launch', 'create3_nodes.launch.py'])
     create3_ignition_nodes_launch = PathJoinSubstitution(
@@ -99,7 +99,7 @@ def generate_launch_description():
     param_file_cmd = DeclareLaunchArgument(
         'param_file',
         default_value=PathJoinSubstitution(
-            [pkg_turtlebot4_ignition_bringup, 'config', 'turtlebot4_node.yaml']),
+            [pkg_turtlebot4_gz_bringup, 'config', 'turtlebot4_node.yaml']),
         description='Turtlebot4 Robot param file')
 
     # Launch configurations
@@ -143,7 +143,7 @@ def generate_launch_description():
 
         # Spawn TurtleBot 4
         Node(
-            package='ros_ign_gazebo',
+            package='ros_gz_sim',
             executable='create',
             arguments=['-name', robot_name,
                        '-x', x,
@@ -156,7 +156,7 @@ def generate_launch_description():
 
         # Spawn Dock
         Node(
-            package='ros_ign_gazebo',
+            package='ros_gz_sim',
             executable='create',
             arguments=['-name', dock_name,
                        '-x', x_dock,
diff --git a/turtlebot4_ignition_bringup/package.xml b/turtlebot4_gz_bringup/package.xml
similarity index 83%
rename from turtlebot4_ignition_bringup/package.xml
rename to turtlebot4_gz_bringup/package.xml
index 352013d..93a4be6 100644
--- a/turtlebot4_ignition_bringup/package.xml
+++ b/turtlebot4_gz_bringup/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
 <package format="3">
-  <name>turtlebot4_ignition_bringup</name>
+  <name>turtlebot4_gz_bringup</name>
   <version>1.0.2</version>
   <description>TurtleBot 4 Ignition Simulator bringup</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
@@ -15,8 +15,8 @@
   <depend>turtlebot4_navigation</depend>
   <depend>turtlebot4_node</depend>
   <depend>turtlebot4_viz</depend>
-  <depend>turtlebot4_ignition_gui_plugins</depend>
-  <depend>turtlebot4_ignition_toolbox</depend>
+  <depend>turtlebot4_gz_gui_plugins</depend>
+  <depend>turtlebot4_gz_toolbox</depend>
 
   <!-- Create3 -->
   <depend>irobot_create_description</depend>
@@ -27,9 +27,9 @@
   <depend>irobot_create_ignition_toolbox</depend>
 
   <!-- ROS IGN -->
-  <depend>ros_ign_interfaces</depend>
-  <depend>ros_ign_gazebo</depend>
-  <depend>ros_ign_bridge</depend>
+  <depend>ros_gz_interfaces</depend>
+  <depend>ros_gz_sim</depend>
+  <!--<depend>ros_ign_bridge</depend>-->
 
   <!-- Messages -->
   <depend>std_msgs</depend>
diff --git a/turtlebot4_ignition_bringup/worlds/depot.sdf b/turtlebot4_gz_bringup/worlds/depot.sdf
similarity index 100%
rename from turtlebot4_ignition_bringup/worlds/depot.sdf
rename to turtlebot4_gz_bringup/worlds/depot.sdf
diff --git a/turtlebot4_ignition_bringup/worlds/maze.sdf b/turtlebot4_gz_bringup/worlds/maze.sdf
similarity index 100%
rename from turtlebot4_ignition_bringup/worlds/maze.sdf
rename to turtlebot4_gz_bringup/worlds/maze.sdf
diff --git a/turtlebot4_ignition_bringup/worlds/warehouse.sdf b/turtlebot4_gz_bringup/worlds/warehouse.sdf
similarity index 100%
rename from turtlebot4_ignition_bringup/worlds/warehouse.sdf
rename to turtlebot4_gz_bringup/worlds/warehouse.sdf
diff --git a/turtlebot4_ignition_gui_plugins/CHANGELOG.rst b/turtlebot4_gz_gui_plugins/CHANGELOG.rst
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/CHANGELOG.rst
rename to turtlebot4_gz_gui_plugins/CHANGELOG.rst
diff --git a/turtlebot4_ignition_gui_plugins/CMakeLists.txt b/turtlebot4_gz_gui_plugins/CMakeLists.txt
similarity index 92%
rename from turtlebot4_ignition_gui_plugins/CMakeLists.txt
rename to turtlebot4_gz_gui_plugins/CMakeLists.txt
index f0b40c8..21842f8 100644
--- a/turtlebot4_ignition_gui_plugins/CMakeLists.txt
+++ b/turtlebot4_gz_gui_plugins/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 3.8)
-project(turtlebot4_ignition_gui_plugins)
+project(turtlebot4_gz_gui_plugins)
 
 if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
   add_compile_options(-Wall -Wextra -Wpedantic)
diff --git a/turtlebot4_gz_gui_plugins/README.md b/turtlebot4_gz_gui_plugins/README.md
new file mode 100644
index 0000000..4a997f3
--- /dev/null
+++ b/turtlebot4_gz_gui_plugins/README.md
@@ -0,0 +1 @@
+# turtlebot4_gz_gui_plugins
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/CMakeLists.txt b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.config b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.config
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.config
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.config
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qrc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qrc
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qrc
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qrc
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/One Dot.png b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/One Dot.png
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/One Dot.png
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/One Dot.png
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/Power.png b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/Power.png
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/Power.png
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/Power.png
diff --git a/turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/Two Dots.png b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/Two Dots.png
similarity index 100%
rename from turtlebot4_ignition_gui_plugins/Turtlebot4Hmi/images/Two Dots.png
rename to turtlebot4_gz_gui_plugins/Turtlebot4Hmi/images/Two Dots.png
diff --git a/turtlebot4_ignition_gui_plugins/package.xml b/turtlebot4_gz_gui_plugins/package.xml
similarity index 93%
rename from turtlebot4_ignition_gui_plugins/package.xml
rename to turtlebot4_gz_gui_plugins/package.xml
index c7f81e2..2881d57 100644
--- a/turtlebot4_ignition_gui_plugins/package.xml
+++ b/turtlebot4_gz_gui_plugins/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
 <package format="3">
-  <name>turtlebot4_ignition_gui_plugins</name>
+  <name>turtlebot4_gz_gui_plugins</name>
   <version>1.0.2</version>
   <description>Turtlebot4 Ignition Simulator GUI Plugins</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
diff --git a/turtlebot4_ignition_toolbox/CHANGELOG.rst b/turtlebot4_gz_toolbox/CHANGELOG.rst
similarity index 100%
rename from turtlebot4_ignition_toolbox/CHANGELOG.rst
rename to turtlebot4_gz_toolbox/CHANGELOG.rst
diff --git a/turtlebot4_ignition_toolbox/CMakeLists.txt b/turtlebot4_gz_toolbox/CMakeLists.txt
similarity index 94%
rename from turtlebot4_ignition_toolbox/CMakeLists.txt
rename to turtlebot4_gz_toolbox/CMakeLists.txt
index 20024d2..5d03643 100644
--- a/turtlebot4_ignition_toolbox/CMakeLists.txt
+++ b/turtlebot4_gz_toolbox/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 3.8)
-project(turtlebot4_ignition_toolbox)
+project(turtlebot4_gz_toolbox)
 
 # Default to C99
 if(NOT CMAKE_C_STANDARD)
@@ -48,7 +48,7 @@ target_link_libraries(${PROJECT_NAME}_lib ${GPIOD_LIBRARY})
 
 ament_target_dependencies(${PROJECT_NAME}_lib ${DEPENDENCIES})
 
-set(EXECUTABLE_NAME "turtlebot4_ignition_hmi_node")
+set(EXECUTABLE_NAME "turtlebot4_gz_hmi_node")
 
 add_executable(${EXECUTABLE_NAME} src/hmi_main.cpp)
 target_link_libraries(${EXECUTABLE_NAME} ${PROJECT_NAME}_lib)
diff --git a/turtlebot4_ignition_toolbox/include/turtlebot4_ignition_toolbox/hmi_node.hpp b/turtlebot4_gz_toolbox/include/turtlebot4_gz_toolbox/hmi_node.hpp
similarity index 87%
rename from turtlebot4_ignition_toolbox/include/turtlebot4_ignition_toolbox/hmi_node.hpp
rename to turtlebot4_gz_toolbox/include/turtlebot4_gz_toolbox/hmi_node.hpp
index ddcfa74..4cdf93b 100644
--- a/turtlebot4_ignition_toolbox/include/turtlebot4_ignition_toolbox/hmi_node.hpp
+++ b/turtlebot4_gz_toolbox/include/turtlebot4_gz_toolbox/hmi_node.hpp
@@ -16,8 +16,8 @@
  * @author Roni Kreinin (rkreinin@clearpathrobotics.com)
  */
 
-#ifndef TURTLEBOT4_IGNITION_TOOLBOX__HMI_NODE_HPP_
-#define TURTLEBOT4_IGNITION_TOOLBOX__HMI_NODE_HPP_
+#ifndef TURTLEBOT4_GZ_TOOLBOX__HMI_NODE_HPP_
+#define TURTLEBOT4_GZ_TOOLBOX__HMI_NODE_HPP_
 
 #include <string>
 
@@ -28,7 +28,7 @@
 #include "turtlebot4_msgs/msg/user_button.hpp"
 #include "turtlebot4_msgs/msg/user_display.hpp"
 
-namespace turtlebot4_ignition_toolbox
+namespace turtlebot4_gz_toolbox
 {
 
 static constexpr auto DISPLAY_CHAR_PER_LINE_HEADER = 21;
@@ -52,6 +52,6 @@ class Hmi : public rclcpp::Node
   rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr button_subscriber_;
 };
 
-}  // namespace turtlebot4_ignition_toolbox
+}  // namespace turtlebot4_gz_toolbox
 
-#endif  // TURTLEBOT4_IGNITION_TOOLBOX__HMI_NODE_HPP_
+#endif  // TURTLEBOT4_GZ_TOOLBOX__HMI_NODE_HPP_
diff --git a/turtlebot4_ignition_toolbox/package.xml b/turtlebot4_gz_toolbox/package.xml
similarity index 83%
rename from turtlebot4_ignition_toolbox/package.xml
rename to turtlebot4_gz_toolbox/package.xml
index 5cb342f..80b6268 100644
--- a/turtlebot4_ignition_toolbox/package.xml
+++ b/turtlebot4_gz_toolbox/package.xml
@@ -1,9 +1,9 @@
 <?xml version="1.0"?>
 <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
 <package format="3">
-  <name>turtlebot4_ignition_toolbox</name>
+  <name>turtlebot4_gz_toolbox</name>
   <version>1.0.2</version>
-  <description>Turtlebot4 Ignition Toolbox</description>
+  <description>Turtlebot4 Gazebo Toolbox</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
   <license>Apache 2.0</license>
 
@@ -15,7 +15,7 @@
   <depend>std_msgs</depend>
   <depend>sensor_msgs</depend>
   <depend>turtlebot4_msgs</depend>
-  <depend>ros_ign_interfaces</depend>
+  <depend>ros_gz_interfaces</depend>
 
   <test_depend>ament_lint_auto</test_depend>
   <test_depend>ament_lint_common</test_depend>
diff --git a/turtlebot4_ignition_toolbox/src/hmi_main.cpp b/turtlebot4_gz_toolbox/src/hmi_main.cpp
similarity index 86%
rename from turtlebot4_ignition_toolbox/src/hmi_main.cpp
rename to turtlebot4_gz_toolbox/src/hmi_main.cpp
index 8b9fb0f..7be7368 100644
--- a/turtlebot4_ignition_toolbox/src/hmi_main.cpp
+++ b/turtlebot4_gz_toolbox/src/hmi_main.cpp
@@ -16,13 +16,13 @@
  * @author Roni Kreinin (rkreinin@clearpathrobotics.com)
  */
 
-#include "turtlebot4_ignition_toolbox/hmi_node.hpp"
+#include "turtlebot4_gz_toolbox/hmi_node.hpp"
 #include <memory>
 
 int main(int argc, char * argv[])
 {
   rclcpp::init(argc, argv);
-  rclcpp::spin(std::make_shared<turtlebot4_ignition_toolbox::Hmi>());
+  rclcpp::spin(std::make_shared<turtlebot4_gz_toolbox::Hmi>());
   rclcpp::shutdown();
   return 0;
 }
diff --git a/turtlebot4_ignition_toolbox/src/hmi_node.cpp b/turtlebot4_gz_toolbox/src/hmi_node.cpp
similarity index 96%
rename from turtlebot4_ignition_toolbox/src/hmi_node.cpp
rename to turtlebot4_gz_toolbox/src/hmi_node.cpp
index a707a76..e53c0c2 100644
--- a/turtlebot4_ignition_toolbox/src/hmi_node.cpp
+++ b/turtlebot4_gz_toolbox/src/hmi_node.cpp
@@ -20,9 +20,9 @@
 #include <utility>
 #include <memory>
 
-#include "turtlebot4_ignition_toolbox/hmi_node.hpp"
+#include "turtlebot4_gz_toolbox/hmi_node.hpp"
 
-using turtlebot4_ignition_toolbox::Hmi;
+using turtlebot4_gz_toolbox::Hmi;
 
 Hmi::Hmi()
 : rclcpp::Node("hmi_node")
diff --git a/turtlebot4_ignition_bringup/README.md b/turtlebot4_ignition_bringup/README.md
deleted file mode 100644
index defad81..0000000
--- a/turtlebot4_ignition_bringup/README.md
+++ /dev/null
@@ -1 +0,0 @@
-# turtlebot4_ignition
diff --git a/turtlebot4_ignition_gui_plugins/README.md b/turtlebot4_ignition_gui_plugins/README.md
deleted file mode 100644
index 4f86064..0000000
--- a/turtlebot4_ignition_gui_plugins/README.md
+++ /dev/null
@@ -1 +0,0 @@
-# turtlebot4_ignition_gui_plugins
diff --git a/turtlebot4_simulator/package.xml b/turtlebot4_simulator/package.xml
index 61f265a..abf3498 100644
--- a/turtlebot4_simulator/package.xml
+++ b/turtlebot4_simulator/package.xml
@@ -3,15 +3,15 @@
 <package format="3">
   <name>turtlebot4_simulator</name>
   <version>1.0.2</version>
-  <description>TODO: Package description</description>
+  <description>Metapackage for Turtlebot4 simulations</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
   <license>Apache 2.0</license>
 
   <buildtool_depend>ament_cmake</buildtool_depend>
 
-  <depend>turtlebot4_ignition_bringup</depend>
-  <depend>turtlebot4_ignition_gui_plugins</depend>
-  <depend>turtlebot4_ignition_toolbox</depend>
+  <depend>turtlebot4_gz_bringup</depend>
+  <depend>turtlebot4_gz_gui_plugins</depend>
+  <depend>turtlebot4_gz_toolbox</depend>
 
   <export>
     <build_type>ament_cmake</build_type>

From 695ade5cec298d1c4926526c252e42f242b8b14d Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 11:50:13 -0400
Subject: [PATCH 02/29] Update gazebo macros, include paths

---
 .../Turtlebot4Hmi/CMakeLists.txt                 | 16 ++++++++--------
 .../Turtlebot4Hmi/Turtlebot4Hmi.cc               |  2 +-
 .../Turtlebot4Hmi/Turtlebot4Hmi.hh               | 12 ++++++------
 3 files changed, 15 insertions(+), 15 deletions(-)

diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
index f473e62..5014d8e 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
@@ -17,16 +17,16 @@ find_package(Qt5
 )
 
 # Find the Ignition gui library
-find_package(ignition-gui6 REQUIRED)
-find_package(ignition-common4 REQUIRED)
+find_package(gz-gui8 REQUIRED)
+find_package(gz-common5 REQUIRED)
 
-set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${IGNITION-GUI_CXX_FLAGS}")
+set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GZ-GUI_CXX_FLAGS}")
 
 qt5_add_resources(resources_rcc Turtlebot4Hmi.qrc)
 
 include_directories(SYSTEM
-  ${IGNITION-COMMON_INCLUDE_DIRS}
-  ${IGNITION-GUI_INCLUDE_DIRS}
+  ${GZ-COMMON_INCLUDE_DIRS}
+  ${GZ-GUI_INCLUDE_DIRS}
   ${Qt5Core_INCLUDE_DIRS}
   ${Qt5Qml_INCLUDE_DIRS}
   ${Qt5Quick_INCLUDE_DIRS}
@@ -34,8 +34,8 @@ include_directories(SYSTEM
 )
 
 link_directories(
-  ${IGNITION-COMMON_LIBRARY_DIRS}
-  ${IGNITION-GUI_LIBRARY_DIRS}
+  ${GZ-COMMON_LIBRARY_DIRS}
+  ${GZ-GUI_LIBRARY_DIRS}
 )
 
 # Generate examples
@@ -44,7 +44,7 @@ Turtlebot4Hmi.cc
   ${resources_rcc}
 )
 target_link_libraries(Turtlebot4Hmi
-  ${IGNITION-GUI_LIBRARIES}
+  ${GZ-GUI_LIBRARIES}
   ${Qt5Core_LIBRARIES}
   ${Qt5Qml_LIBRARIES}
   ${Qt5Quick_LIBRARIES}
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
index 60a6391..2ad467b 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
@@ -379,6 +379,6 @@ void Turtlebot4Hmi::OnAddMsg(QString msg)
 }
 
 // Register this plugin
-IGNITION_ADD_PLUGIN(
+GZ_ADD_PLUGIN(
   ignition::gui::Turtlebot4Hmi,
   ignition::gui::Plugin)
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
index b89efb7..e304055 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
@@ -16,15 +16,15 @@
  * @author Roni Kreinin (rkreinin@clearpathrobotics.com)
  */
 
-#ifndef TURTLEBOT4_IGNITION_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
-#define TURTLEBOT4_IGNITION_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
+#ifndef TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
+#define TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
 
-#include <ignition/gui/qt.h>
+#include <gz/gui/qt.h>
 
 #include <string>
 
-#include <ignition/transport/Node.hh>
-#include <ignition/gui/Plugin.hh>
+#include <gz/transport/Node.hh>
+#include <gz/gui/Plugin.hh>
 
 namespace ignition
 {
@@ -135,4 +135,4 @@ private:
 
 }  // namespace ignition
 
-#endif  // TURTLEBOT4_IGNITION_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
+#endif  // TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_

From 5c005f750adebfe1f2dc860279d7e69962ed23f7 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 11:51:00 -0400
Subject: [PATCH 03/29] More include paths

---
 turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
index 2ad467b..2ccaa26 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
@@ -23,9 +23,9 @@
 #include <iostream>
 #include <vector>
 
-#include <ignition/plugin/Register.hh>
-#include <ignition/gui/Application.hh>
-#include <ignition/gui/MainWindow.hh>
+#include <gz/plugin/Register.hh>
+#include <gz/gui/Application.hh>
+#include <gz/gui/MainWindow.hh>
 
 using ignition::gui::Turtlebot4Hmi;
 

From 6c2940c363412a049eb05921d6e2b35cf9e3a1af Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 11:58:27 -0400
Subject: [PATCH 04/29] Namespace replacements

---
 .../Turtlebot4Hmi/Turtlebot4Hmi.cc            | 42 +++++++++----------
 .../Turtlebot4Hmi/Turtlebot4Hmi.hh            | 28 ++++++-------
 2 files changed, 35 insertions(+), 35 deletions(-)

diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
index 2ccaa26..524903c 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
@@ -18,7 +18,7 @@
 
 #include "Turtlebot4Hmi.hh"
 
-#include <ignition/msgs/int32.pb.h>
+#include <gz/msgs/int32.pb.h>
 
 #include <iostream>
 #include <vector>
@@ -27,7 +27,7 @@
 #include <gz/gui/Application.hh>
 #include <gz/gui/MainWindow.hh>
 
-using ignition::gui::Turtlebot4Hmi;
+using gz::gui::Turtlebot4Hmi;
 
 Turtlebot4Hmi::Turtlebot4Hmi()
 : Plugin()
@@ -43,10 +43,10 @@ Turtlebot4Hmi::~Turtlebot4Hmi()
 
 void Turtlebot4Hmi::CreatePublishers()
 {
-  this->hmi_button_pub_ = ignition::transport::Node::Publisher();
-  this->hmi_button_pub_ = this->node_.Advertise < ignition::msgs::Int32 > (this->hmi_button_topic_);
-  this->create3_button_pub_ = ignition::transport::Node::Publisher();
-  this->create3_button_pub_ = this->node_.Advertise < ignition::msgs::Int32 > (
+  this->hmi_button_pub_ = gz::transport::Node::Publisher();
+  this->hmi_button_pub_ = this->node_.Advertise < gz::msgs::Int32 > (this->hmi_button_topic_);
+  this->create3_button_pub_ = gz::transport::Node::Publisher();
+  this->create3_button_pub_ = this->node_.Advertise < gz::msgs::Int32 > (
     this->create3_button_topic_);
 }
 
@@ -140,41 +140,41 @@ void Turtlebot4Hmi::SetNamespace(const QString &_name)
 
 void Turtlebot4Hmi::OnHmiButton(const int button)
 {
-  ignition::msgs::Int32 button_msg;
+  gz::msgs::Int32 button_msg;
 
   button_msg.set_data(button);
 
   if (!this->hmi_button_pub_.Publish(button_msg)) {
-    ignerr << "ignition::msgs::Int32 message couldn't be published at topic: " <<
+    ignerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
       this->hmi_button_topic_ << std::endl;
   }
 }
 
 void Turtlebot4Hmi::OnCreate3Button(const int button)
 {
-  ignition::msgs::Int32 button_msg;
+  gz::msgs::Int32 button_msg;
 
   button_msg.set_data(button);
 
   if (!this->create3_button_pub_.Publish(button_msg)) {
-    ignerr << "ignition::msgs::Int32 message couldn't be published at topic: " <<
+    ignerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
       this->create3_button_topic_ << std::endl;
   }
 }
 
-void Turtlebot4Hmi::OnRawMessage(const ignition::msgs::StringMsg & msg)
+void Turtlebot4Hmi::OnRawMessage(const gz::msgs::StringMsg & msg)
 {
   std::lock_guard < std::mutex > lock(this->raw_msg_mutex_);
   this->AddMsg(QString::fromStdString(msg.data()));
 }
 
-void Turtlebot4Hmi::OnSelectedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnSelectedMessage(const gz::msgs::Int32 & msg)
 {
   std::lock_guard < std::mutex > lock(this->selected_msg_mutex_);
   selected_line_ = msg.data();
 }
 
-void Turtlebot4Hmi::OnPowerLedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnPowerLedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -194,7 +194,7 @@ void Turtlebot4Hmi::OnPowerLedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnMotorsLedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnMotorsLedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -214,7 +214,7 @@ void Turtlebot4Hmi::OnMotorsLedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnCommsLedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnCommsLedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -234,7 +234,7 @@ void Turtlebot4Hmi::OnCommsLedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnWifiLedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnWifiLedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -254,7 +254,7 @@ void Turtlebot4Hmi::OnWifiLedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnBatteryLedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnBatteryLedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -286,7 +286,7 @@ void Turtlebot4Hmi::OnBatteryLedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnUser1LedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnUser1LedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -306,7 +306,7 @@ void Turtlebot4Hmi::OnUser1LedMessage(const ignition::msgs::Int32 & msg)
   }
 }
 
-void Turtlebot4Hmi::OnUser2LedMessage(const ignition::msgs::Int32 & msg)
+void Turtlebot4Hmi::OnUser2LedMessage(const gz::msgs::Int32 & msg)
 {
   switch (msg.data()) {
     case 0:
@@ -380,5 +380,5 @@ void Turtlebot4Hmi::OnAddMsg(QString msg)
 
 // Register this plugin
 GZ_ADD_PLUGIN(
-  ignition::gui::Turtlebot4Hmi,
-  ignition::gui::Plugin)
+  gz::gui::Turtlebot4Hmi,
+  gz::gui::Plugin)
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
index e304055..a73c66f 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
@@ -26,7 +26,7 @@
 #include <gz/transport/Node.hh>
 #include <gz/gui/Plugin.hh>
 
-namespace ignition
+namespace gz
 {
 
 namespace gui
@@ -82,15 +82,15 @@ signals:
 
   /// \brief Subscriber callbacks
 private:
-  void OnRawMessage(const ignition::msgs::StringMsg & msg);
-  void OnSelectedMessage(const ignition::msgs::Int32 & msg);
-  void OnPowerLedMessage(const ignition::msgs::Int32 & msg);
-  void OnMotorsLedMessage(const ignition::msgs::Int32 & msg);
-  void OnCommsLedMessage(const ignition::msgs::Int32 & msg);
-  void OnWifiLedMessage(const ignition::msgs::Int32 & msg);
-  void OnBatteryLedMessage(const ignition::msgs::Int32 & msg);
-  void OnUser1LedMessage(const ignition::msgs::Int32 & msg);
-  void OnUser2LedMessage(const ignition::msgs::Int32 & msg);
+  void OnRawMessage(const gz::msgs::StringMsg & msg);
+  void OnSelectedMessage(const gz::msgs::Int32 & msg);
+  void OnPowerLedMessage(const gz::msgs::Int32 & msg);
+  void OnMotorsLedMessage(const gz::msgs::Int32 & msg);
+  void OnCommsLedMessage(const gz::msgs::Int32 & msg);
+  void OnWifiLedMessage(const gz::msgs::Int32 & msg);
+  void OnBatteryLedMessage(const gz::msgs::Int32 & msg);
+  void OnUser1LedMessage(const gz::msgs::Int32 & msg);
+  void OnUser2LedMessage(const gz::msgs::Int32 & msg);
   void CreatePublishers();
   void CreateSubscribers();
   void RemovePublishers();
@@ -103,9 +103,9 @@ private slots:
   void OnAddMsg(QString msg);
 
 private:
-  ignition::transport::Node node_;
-  ignition::transport::Node::Publisher hmi_button_pub_;
-  ignition::transport::Node::Publisher create3_button_pub_;
+  gz::transport::Node node_;
+  gz::transport::Node::Publisher hmi_button_pub_;
+  gz::transport::Node::Publisher create3_button_pub_;
 
   std::string namespace_ = "";
   std::string hmi_button_topic_ = "/hmi/buttons";
@@ -133,6 +133,6 @@ private:
 
 }  // namespace gui
 
-}  // namespace ignition
+}  // namespace gz
 
 #endif  // TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_

From 10ec301ac3c7803127fc631ebab6e58b3cdbd031 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 12:14:34 -0400
Subject: [PATCH 05/29] Include messages in the header

---
 turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh | 1 +
 1 file changed, 1 insertion(+)

diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
index a73c66f..db26b10 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
@@ -20,6 +20,7 @@
 #define TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
 
 #include <gz/gui/qt.h>
+#include <gz/msgs.hh>
 
 #include <string>
 

From 2eeb00baacf8f0fb4a172ffd0ff7d7355316d3ef Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 16 Jul 2024 12:22:27 -0400
Subject: [PATCH 06/29] Update dependencies

---
 turtlebot4_gz_gui_plugins/package.xml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_gui_plugins/package.xml b/turtlebot4_gz_gui_plugins/package.xml
index 2881d57..2c5590e 100644
--- a/turtlebot4_gz_gui_plugins/package.xml
+++ b/turtlebot4_gz_gui_plugins/package.xml
@@ -8,7 +8,7 @@
   <license>Apache 2.0</license>
 
   <buildtool_depend>ament_cmake</buildtool_depend>
-  <buildtool_depend>ignition-gui6</buildtool_depend>
+  <buildtool_depend>gz-gui8</buildtool_depend>
   <depend>qml-module-qtquick-extras</depend>
 
   <test_depend>ament_lint_auto</test_depend>

From 483a3a888b038963f8f6b9f8534c15780368eba7 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 10:49:03 -0400
Subject: [PATCH 07/29] create_ignition -> create_gz

---
 turtlebot4_gz_bringup/launch/gazebo.launch.py        | 12 ++++++------
 turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py |  6 +++---
 .../launch/turtlebot4_spawn.launch.py                |  6 +++---
 turtlebot4_gz_bringup/package.xml                    |  4 ++--
 4 files changed, 14 insertions(+), 14 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/gazebo.launch.py b/turtlebot4_gz_bringup/launch/gazebo.launch.py
index 9672e6a..eeb84e6 100644
--- a/turtlebot4_gz_bringup/launch/gazebo.launch.py
+++ b/turtlebot4_gz_bringup/launch/gazebo.launch.py
@@ -51,10 +51,10 @@ def generate_launch_description():
         'turtlebot4_description')
     pkg_irobot_create_description = get_package_share_directory(
         'irobot_create_description')
-    pkg_irobot_create_ignition_bringup = get_package_share_directory(
-        'irobot_create_ignition_bringup')
-    pkg_irobot_create_ignition_plugins = get_package_share_directory(
-        'irobot_create_ignition_plugins')
+    pkg_irobot_create_gz_bringup = get_package_share_directory(
+        'irobot_create_gz_bringup')
+    pkg_irobot_create_gz_plugins = get_package_share_directory(
+        'irobot_create_gz_plugins')
     pkg_ros_gz_sim = get_package_share_directory(
         'ros_gz_sim')
 
@@ -63,7 +63,7 @@ def generate_launch_description():
         name='GZ_GAZEBO_RESOURCE_PATH',
         value=[
             os.path.join(pkg_turtlebot4_gz_bringup, 'worlds'), ':' +
-            os.path.join(pkg_irobot_create_ignition_bringup, 'worlds'), ':' +
+            os.path.join(pkg_irobot_create_gz_bringup, 'worlds'), ':' +
             str(Path(pkg_turtlebot4_description).parent.resolve()), ':' +
             str(Path(pkg_irobot_create_description).parent.resolve())])
 
@@ -71,7 +71,7 @@ def generate_launch_description():
         name='GZ_GUI_PLUGIN_PATH',
         value=[
             os.path.join(pkg_turtlebot4_gz_gui_plugins, 'lib'), ':' +
-            os.path.join(pkg_irobot_create_ignition_plugins, 'lib')])
+            os.path.join(pkg_irobot_create_gz_plugins, 'lib')])
 
     # Paths
     gz_sim_launch = PathJoinSubstitution(
diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index a874416..a220e91 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -60,11 +60,11 @@ def generate_launch_description():
         'user2'
     ]
 
-    pkg_irobot_create_ignition_bringup = get_package_share_directory(
-        'irobot_create_ignition_bringup')
+    pkg_irobot_create_gz_bringup = get_package_share_directory(
+        'irobot_create_gz_bringup')
 
     create3_ros_gz_bridge_launch = PathJoinSubstitution(
-        [pkg_irobot_create_ignition_bringup, 'launch', 'create3_ros_ignition_bridge.launch.py'])
+        [pkg_irobot_create_gz_bringup, 'launch', 'create3_ros_ignition_bridge.launch.py'])
 
     create3_bridge = IncludeLaunchDescription(
         PythonLaunchDescriptionSource([create3_ros_gz_bridge_launch]),
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index 34df9d0..53efb17 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -70,8 +70,8 @@ def generate_launch_description():
         'turtlebot4_navigation')
     pkg_irobot_create_common_bringup = get_package_share_directory(
         'irobot_create_common_bringup')
-    pkg_irobot_create_ignition_bringup = get_package_share_directory(
-        'irobot_create_ignition_bringup')
+    pkg_irobot_create_gz_bringup = get_package_share_directory(
+        'irobot_create_gz_bringup')
 
     # Paths
     turtlebot4_ros_ign_bridge_launch = PathJoinSubstitution(
@@ -83,7 +83,7 @@ def generate_launch_description():
     create3_nodes_launch = PathJoinSubstitution(
         [pkg_irobot_create_common_bringup, 'launch', 'create3_nodes.launch.py'])
     create3_ignition_nodes_launch = PathJoinSubstitution(
-        [pkg_irobot_create_ignition_bringup, 'launch', 'create3_ignition_nodes.launch.py'])
+        [pkg_irobot_create_gz_bringup, 'launch', 'create3_ignition_nodes.launch.py'])
     robot_description_launch = PathJoinSubstitution(
         [pkg_turtlebot4_description, 'launch', 'robot_description.launch.py'])
     dock_description_launch = PathJoinSubstitution(
diff --git a/turtlebot4_gz_bringup/package.xml b/turtlebot4_gz_bringup/package.xml
index 93a4be6..f929021 100644
--- a/turtlebot4_gz_bringup/package.xml
+++ b/turtlebot4_gz_bringup/package.xml
@@ -23,8 +23,8 @@
   <depend>irobot_create_common_bringup</depend>
   <depend>irobot_create_nodes</depend>
   <depend>irobot_create_toolbox</depend>
-  <depend>irobot_create_ignition_bringup</depend>
-  <depend>irobot_create_ignition_toolbox</depend>
+  <depend>irobot_create_gz_bringup</depend>
+  <depend>irobot_create_gz_toolbox</depend>
 
   <!-- ROS IGN -->
   <depend>ros_gz_interfaces</depend>

From a4361b2ccc9f7010a917379886d785f50d911459 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 11:32:46 -0400
Subject: [PATCH 08/29] Rename more launch files

---
 .../launch/turtlebot4_spawn.launch.py              | 14 +++++++-------
 1 file changed, 7 insertions(+), 7 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index 53efb17..265e243 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -74,16 +74,16 @@ def generate_launch_description():
         'irobot_create_gz_bringup')
 
     # Paths
-    turtlebot4_ros_ign_bridge_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_gz_bringup, 'launch', 'ros_ign_bridge.launch.py'])
+    turtlebot4_ros_gz_bridge_launch = PathJoinSubstitution(
+        [pkg_turtlebot4_gz_bringup, 'launch', 'ros_gz_bridge.launch.py'])
     rviz_launch = PathJoinSubstitution(
         [pkg_turtlebot4_viz, 'launch', 'view_robot.launch.py'])
     turtlebot4_node_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_nodes.launch.py'])
     create3_nodes_launch = PathJoinSubstitution(
         [pkg_irobot_create_common_bringup, 'launch', 'create3_nodes.launch.py'])
-    create3_ignition_nodes_launch = PathJoinSubstitution(
-        [pkg_irobot_create_gz_bringup, 'launch', 'create3_ignition_nodes.launch.py'])
+    create3_gz_nodes_launch = PathJoinSubstitution(
+        [pkg_irobot_create_gz_bringup, 'launch', 'create3_gz_nodes.launch.py'])
     robot_description_launch = PathJoinSubstitution(
         [pkg_turtlebot4_description, 'launch', 'robot_description.launch.py'])
     dock_description_launch = PathJoinSubstitution(
@@ -138,7 +138,7 @@ def generate_launch_description():
         IncludeLaunchDescription(
             PythonLaunchDescriptionSource([dock_description_launch]),
             # The robot starts docked
-            launch_arguments={'gazebo': 'ignition'}.items(),
+            launch_arguments={'gazebo': 'harmonic'}.items(),
         ),
 
         # Spawn TurtleBot 4
@@ -169,7 +169,7 @@ def generate_launch_description():
 
         # ROS IGN bridge
         IncludeLaunchDescription(
-            PythonLaunchDescriptionSource([turtlebot4_ros_ign_bridge_launch]),
+            PythonLaunchDescriptionSource([turtlebot4_ros_gz_bridge_launch]),
             launch_arguments=[
                 ('model', LaunchConfiguration('model')),
                 ('robot_name', robot_name),
@@ -194,7 +194,7 @@ def generate_launch_description():
 
         # Create 3 Ignition nodes
         IncludeLaunchDescription(
-            PythonLaunchDescriptionSource([create3_ignition_nodes_launch]),
+            PythonLaunchDescriptionSource([create3_gz_nodes_launch]),
             launch_arguments=[
                 ('robot_name', robot_name),
                 ('dock_name', dock_name),

From 070776820f28769c2af8f4c1134df6b02de1feb9 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 11:36:09 -0400
Subject: [PATCH 09/29] Revert launch argument change

---
 turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index 265e243..d1b08a8 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -138,7 +138,7 @@ def generate_launch_description():
         IncludeLaunchDescription(
             PythonLaunchDescriptionSource([dock_description_launch]),
             # The robot starts docked
-            launch_arguments={'gazebo': 'harmonic'}.items(),
+            launch_arguments={'gazebo': 'ignition'}.items(),
         ),
 
         # Spawn TurtleBot 4

From e2bc7021c1c612daf352cf61ef5ae37532cafe84 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 11:38:59 -0400
Subject: [PATCH 10/29] More ignition renames

---
 turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py   |  2 +-
 .../launch/turtlebot4_gazebo.launch.py                 | 10 +++++-----
 2 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index a220e91..c9f2e09 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -64,7 +64,7 @@ def generate_launch_description():
         'irobot_create_gz_bringup')
 
     create3_ros_gz_bridge_launch = PathJoinSubstitution(
-        [pkg_irobot_create_gz_bringup, 'launch', 'create3_ros_ignition_bridge.launch.py'])
+        [pkg_irobot_create_gz_bringup, 'launch', 'create3_ros_gz_bridge.launch.py'])
 
     create3_bridge = IncludeLaunchDescription(
         PythonLaunchDescriptionSource([create3_ros_gz_bridge_launch]),
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
index 90dbfd1..f8ddbb7 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
@@ -29,7 +29,7 @@
     DeclareLaunchArgument('rviz', default_value='false',
                           choices=['true', 'false'], description='Start rviz.'),
     DeclareLaunchArgument('world', default_value='warehouse',
-                          description='Ignition World'),
+                          description='Simulation World'),
     DeclareLaunchArgument('model', default_value='standard',
                           choices=['standard', 'lite'],
                           description='Turtlebot4 Model'),
@@ -46,13 +46,13 @@ def generate_launch_description():
         'turtlebot4_gz_bringup')
 
     # Paths
-    ignition_launch = PathJoinSubstitution(
+    gazebo_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'gazebo.launch.py'])
     robot_spawn_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_spawn.launch.py'])
 
-    ignition = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource([ignition_launch]),
+    gazebo = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource([gazebo_launch]),
         launch_arguments=[
             ('world', LaunchConfiguration('world'))
         ]
@@ -71,6 +71,6 @@ def generate_launch_description():
 
     # Create launch description and add actions
     ld = LaunchDescription(ARGUMENTS)
-    ld.add_action(ignition)
+    ld.add_action(gazebo)
     ld.add_action(robot_spawn)
     return ld

From b52c75f1b13cde0b235e9f4080ae56df2d3885d2 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 11:45:41 -0400
Subject: [PATCH 11/29] Remove depcreated condition checks

---
 turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py    | 8 ++++----
 turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py | 4 ++--
 2 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index c9f2e09..bf765a9 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -18,7 +18,7 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
-from launch.conditions import LaunchConfigurationEquals
+from launch.conditions import EqualsSubstitution
 from launch.launch_description_sources import PythonLaunchDescriptionSource
 from launch.substitutions import LaunchConfiguration
 from launch.substitutions.path_join_substitution import PathJoinSubstitution
@@ -119,7 +119,7 @@ def generate_launch_description():
             ([namespace, '/hmi/display/selected'],
              'hmi/display/_selected')
         ],
-        condition=LaunchConfigurationEquals('model', 'standard'))
+        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
 
     # Buttons message bridge
     hmi_buttons_msg_bridge = Node(
@@ -137,7 +137,7 @@ def generate_launch_description():
             ([namespace, '/hmi/buttons'],
              'hmi/buttons/_set')
         ],
-        condition=LaunchConfigurationEquals('model', 'standard'))
+        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
 
     # Buttons message bridge
     hmi_led_msg_bridge = Node(
@@ -155,7 +155,7 @@ def generate_launch_description():
             ([namespace, '/hmi/led/' + led],
              'hmi/led/_' + led) for led in leds
         ],
-        condition=LaunchConfigurationEquals('model', 'standard'))
+        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
 
     # Camera sensor bridge
     oakd_camera_bridge = Node(
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
index 19eca96..db54e9d 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
@@ -18,7 +18,7 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument
-from launch.conditions import LaunchConfigurationEquals
+from launch.conditions import EqualsSubstitution
 from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
 from launch_ros.actions import Node
 
@@ -60,7 +60,7 @@ def generate_launch_description():
         name='turtlebot4_gz_hmi_node',
         executable='turtlebot4_gz_hmi_node',
         output='screen',
-        condition=LaunchConfigurationEquals('model', 'standard')
+        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard')
     )
 
     # Define LaunchDescription variable

From 3a19e116eace1d7fe99f406f761fd8c160e03bb1 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 12:10:32 -0400
Subject: [PATCH 12/29] Fix imports

---
 turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py    | 3 +--
 turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py | 3 +--
 2 files changed, 2 insertions(+), 4 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index bf765a9..e239fc1 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -18,9 +18,8 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
-from launch.conditions import EqualsSubstitution
 from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch.substitutions import LaunchConfiguration
+from launch.substitutions import EqualsSubstitution, LaunchConfiguration
 from launch.substitutions.path_join_substitution import PathJoinSubstitution
 
 from launch_ros.actions import Node
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
index db54e9d..8a39b35 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
@@ -18,8 +18,7 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument
-from launch.conditions import EqualsSubstitution
-from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
+from launch.substitutions import EqualsSubstitution, LaunchConfiguration, PathJoinSubstitution
 from launch_ros.actions import Node
 
 ARGUMENTS = [

From cc608b2494bfb0ca574d8b1762b736e0c3bcf460 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 17 Jul 2024 12:18:55 -0400
Subject: [PATCH 13/29] IfCondition wrappers

---
 turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py    | 7 ++++---
 turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py | 3 ++-
 2 files changed, 6 insertions(+), 4 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index e239fc1..479f26b 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -18,6 +18,7 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.conditions import IfCondition
 from launch.launch_description_sources import PythonLaunchDescriptionSource
 from launch.substitutions import EqualsSubstitution, LaunchConfiguration
 from launch.substitutions.path_join_substitution import PathJoinSubstitution
@@ -118,7 +119,7 @@ def generate_launch_description():
             ([namespace, '/hmi/display/selected'],
              'hmi/display/_selected')
         ],
-        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
+        condition=IfCondition(EqualsSubstitution(LaunchConfiguration('model'), 'standard')))
 
     # Buttons message bridge
     hmi_buttons_msg_bridge = Node(
@@ -136,7 +137,7 @@ def generate_launch_description():
             ([namespace, '/hmi/buttons'],
              'hmi/buttons/_set')
         ],
-        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
+        condition=IfCondition(EqualsSubstitution(LaunchConfiguration('model'), 'standard')))
 
     # Buttons message bridge
     hmi_led_msg_bridge = Node(
@@ -154,7 +155,7 @@ def generate_launch_description():
             ([namespace, '/hmi/led/' + led],
              'hmi/led/_' + led) for led in leds
         ],
-        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
+        condition=IfCondition(EqualsSubstitution(LaunchConfiguration('model'), 'standard')))
 
     # Camera sensor bridge
     oakd_camera_bridge = Node(
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
index 8a39b35..4388478 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
@@ -18,6 +18,7 @@
 
 from launch import LaunchDescription
 from launch.actions import DeclareLaunchArgument
+from launch.conditions import IfCondition
 from launch.substitutions import EqualsSubstitution, LaunchConfiguration, PathJoinSubstitution
 from launch_ros.actions import Node
 
@@ -59,7 +60,7 @@ def generate_launch_description():
         name='turtlebot4_gz_hmi_node',
         executable='turtlebot4_gz_hmi_node',
         output='screen',
-        condition=EqualsSubstitution(LaunchConfiguration('model'), 'standard')
+        condition=IfCondition(EqualsSubstitution(LaunchConfiguration('model'), 'standard'))
     )
 
     # Define LaunchDescription variable

From e5839f8e8f1e184e6f98f79433edfa9024241390 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 23 Jul 2024 13:30:43 -0400
Subject: [PATCH 14/29] Rename gazebo -> sim/gz, fix resource path envar

---
 .../launch/{gazebo.launch.py => sim.launch.py}                  | 2 +-
 .../{turtlebot4_gazebo.launch.py => turtlebot4_gz.launch.py}    | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)
 rename turtlebot4_gz_bringup/launch/{gazebo.launch.py => sim.launch.py} (99%)
 mode change 100644 => 100755
 rename turtlebot4_gz_bringup/launch/{turtlebot4_gazebo.launch.py => turtlebot4_gz.launch.py} (97%)
 mode change 100644 => 100755

diff --git a/turtlebot4_gz_bringup/launch/gazebo.launch.py b/turtlebot4_gz_bringup/launch/sim.launch.py
old mode 100644
new mode 100755
similarity index 99%
rename from turtlebot4_gz_bringup/launch/gazebo.launch.py
rename to turtlebot4_gz_bringup/launch/sim.launch.py
index eeb84e6..fe23a22
--- a/turtlebot4_gz_bringup/launch/gazebo.launch.py
+++ b/turtlebot4_gz_bringup/launch/sim.launch.py
@@ -60,7 +60,7 @@ def generate_launch_description():
 
     # Set ignition resource path
     gz_resource_path = SetEnvironmentVariable(
-        name='GZ_GAZEBO_RESOURCE_PATH',
+        name='GZ_SIM_RESOURCE_PATH',
         value=[
             os.path.join(pkg_turtlebot4_gz_bringup, 'worlds'), ':' +
             os.path.join(pkg_irobot_create_gz_bringup, 'worlds'), ':' +
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py
old mode 100644
new mode 100755
similarity index 97%
rename from turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
rename to turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py
index f8ddbb7..4c7cec6
--- a/turtlebot4_gz_bringup/launch/turtlebot4_gazebo.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py
@@ -47,7 +47,7 @@ def generate_launch_description():
 
     # Paths
     gazebo_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_gz_bringup, 'launch', 'gazebo.launch.py'])
+        [pkg_turtlebot4_gz_bringup, 'launch', 'sim.launch.py'])
     robot_spawn_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_spawn.launch.py'])
 

From 84b2df228401557b1e7f9942720f73285e0856de Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 23 Jul 2024 13:31:33 -0400
Subject: [PATCH 15/29] Fix permissions

---
 turtlebot4_gz_bringup/launch/sim.launch.py           | 0
 turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py | 0
 2 files changed, 0 insertions(+), 0 deletions(-)
 mode change 100755 => 100644 turtlebot4_gz_bringup/launch/sim.launch.py
 mode change 100755 => 100644 turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py

diff --git a/turtlebot4_gz_bringup/launch/sim.launch.py b/turtlebot4_gz_bringup/launch/sim.launch.py
old mode 100755
new mode 100644
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_gz.launch.py
old mode 100755
new mode 100644

From cbfcdb7332e76912053730a838258ebb9b670dd0 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 14:34:05 -0400
Subject: [PATCH 16/29] Update the GUI configurations

---
 turtlebot4_gz_bringup/gui/lite/gui.config     | 50 ++++++++++++-------
 turtlebot4_gz_bringup/gui/standard/gui.config | 50 ++++++++++++-------
 2 files changed, 62 insertions(+), 38 deletions(-)

diff --git a/turtlebot4_gz_bringup/gui/lite/gui.config b/turtlebot4_gz_bringup/gui/lite/gui.config
index 3f512c9..6d2b59e 100644
--- a/turtlebot4_gz_bringup/gui/lite/gui.config
+++ b/turtlebot4_gz_bringup/gui/lite/gui.config
@@ -1,26 +1,38 @@
 <?xml version="1.0" ?>
 
 <!-- 3D scene -->
-<plugin filename="GzScene3D" name="3D View">
-  <ignition-gui>
-    <title>3D View</title>
-    <property type="bool" key="showTitleBar">false</property>
-    <property type="string" key="state">docked</property>
-  </ignition-gui>
-
-  <engine>ogre2</engine>
-  <scene>scene</scene>
-  <camera_pose>-0.0176 -0.737 0.017 0 -0.135 1.64</camera_pose>
+<plugin filename="MinimalScene" name="3D View">
+    <gz-gui>
+      <title>3D View</title>
+      <property key="state" type="string">docked</property>
+      <property key="showTitleBar" type="bool">false</property>
+    </gz-gui>
+    <engine>ogre2</engine>
+    <scene>scene</scene>
+    <ambient_light>0.4 0.4 0.4</ambient_light>
+    <background_color>0.8 0.8 0.8</background_color>
+    <camera_pose>-6 0 6 0 0.5 0</camera_pose>
+</plugin>
+<plugin filename="GzSceneManager" name="Scene Manager">
+    <gz-gui>
+      <property key="visible" type="bool">false</property>
+      <property key="state" type="string">floating</property>
+    </gz-gui>
+</plugin>
+<plugin filename="InteractiveViewControl" name="Interactive view control">
+    <gz-gui>
+        <property key="visible" type="bool">false</property>
+        <property key="state" type="string">floating</property>
+    </gz-gui>
 </plugin>
 
 <!-- Play / pause / step -->
 <plugin filename="WorldControl" name="World control">
-  <ignition-gui>
+  <gz-gui>
     <title>World control</title>
     <property type="bool" key="showTitleBar">false</property>
     <property type="bool" key="resizable">false</property>
     <property type="double" key="height">72</property>
-    <property type="double" key="width">121</property>
     <property type="double" key="z">1</property>
 
     <property type="string" key="state">floating</property>
@@ -28,7 +40,7 @@
       <line own="left" target="left"/>
       <line own="bottom" target="bottom"/>
     </anchors>
-  </ignition-gui>
+  </gz-gui>
 
   <play_pause>true</play_pause>
   <step>true</step>
@@ -37,7 +49,7 @@
 
 <!-- Time / RTF -->
 <plugin filename="WorldStats" name="World stats">
-  <ignition-gui>
+  <gz-gui>
     <title>World stats</title>
     <property type="bool" key="showTitleBar">false</property>
     <property type="bool" key="resizable">false</property>
@@ -50,7 +62,7 @@
       <line own="right" target="right"/>
       <line own="bottom" target="bottom"/>
     </anchors>
-  </ignition-gui>
+  </gz-gui>
 
   <sim_time>true</sim_time>
   <real_time>true</real_time>
@@ -60,7 +72,7 @@
 
 <!-- Translate / rotate -->
 <plugin filename="TransformControl" name="Transform control">
-  <ignition-gui>
+  <gz-gui>
     <title>Transform control</title>
     <anchors target="3D View">
       <line own="left" target="left"/>
@@ -72,12 +84,12 @@
     <property key="state" type="string">floating</property>
     <property key="showTitleBar" type="bool">false</property>
     <property key="cardBackground" type="string">#03a9f4</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- Insert simple shapes -->
 <plugin filename="Shapes" name="Shapes">
-  <ignition-gui>
+  <gz-gui>
     <anchors target="Transform control">
       <line own="left" target="right"/>
       <line own="top" target="top"/>
@@ -88,7 +100,7 @@
     <property key="state" type="string">floating</property>
     <property key="showTitleBar" type="bool">false</property>
     <property key="cardBackground" type="string">#03a9f4</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- HMI -->
diff --git a/turtlebot4_gz_bringup/gui/standard/gui.config b/turtlebot4_gz_bringup/gui/standard/gui.config
index d3c30d8..fc2c77b 100644
--- a/turtlebot4_gz_bringup/gui/standard/gui.config
+++ b/turtlebot4_gz_bringup/gui/standard/gui.config
@@ -1,26 +1,38 @@
 <?xml version="1.0" ?>
 
 <!-- 3D scene -->
-<plugin filename="GzScene3D" name="3D View">
-  <ignition-gui>
-    <title>3D View</title>
-    <property type="bool" key="showTitleBar">false</property>
-    <property type="string" key="state">docked</property>
-  </ignition-gui>
-
-  <engine>ogre2</engine>
-  <scene>scene</scene>
-  <camera_pose>-0.0176 -0.737 0.017 0 -0.135 1.64</camera_pose>
+<plugin filename="MinimalScene" name="3D View">
+    <gz-gui>
+      <title>3D View</title>
+      <property key="state" type="string">docked</property>
+      <property key="showTitleBar" type="bool">false</property>
+    </gz-gui>
+    <engine>ogre2</engine>
+    <scene>scene</scene>
+    <ambient_light>0.4 0.4 0.4</ambient_light>
+    <background_color>0.8 0.8 0.8</background_color>
+    <camera_pose>-6 0 6 0 0.5 0</camera_pose>
+</plugin>
+<plugin filename="GzSceneManager" name="Scene Manager">
+    <gz-gui>
+      <property key="visible" type="bool">false</property>
+      <property key="state" type="string">floating</property>
+    </gz-gui>
+</plugin>
+<plugin filename="InteractiveViewControl" name="Interactive view control">
+    <gz-gui>
+        <property key="visible" type="bool">false</property>
+        <property key="state" type="string">floating</property>
+    </gz-gui>
 </plugin>
 
 <!-- Play / pause / step -->
 <plugin filename="WorldControl" name="World control">
-  <ignition-gui>
+  <gz-gui>
     <title>World control</title>
     <property type="bool" key="showTitleBar">false</property>
     <property type="bool" key="resizable">false</property>
     <property type="double" key="height">72</property>
-    <property type="double" key="width">121</property>
     <property type="double" key="z">1</property>
 
     <property type="string" key="state">floating</property>
@@ -28,7 +40,7 @@
       <line own="left" target="left"/>
       <line own="bottom" target="bottom"/>
     </anchors>
-  </ignition-gui>
+  </gz-gui>
 
   <play_pause>true</play_pause>
   <step>true</step>
@@ -37,7 +49,7 @@
 
 <!-- Time / RTF -->
 <plugin filename="WorldStats" name="World stats">
-  <ignition-gui>
+  <gz-gui>
     <title>World stats</title>
     <property type="bool" key="showTitleBar">false</property>
     <property type="bool" key="resizable">false</property>
@@ -50,7 +62,7 @@
       <line own="right" target="right"/>
       <line own="bottom" target="bottom"/>
     </anchors>
-  </ignition-gui>
+  </gz-gui>
 
   <sim_time>true</sim_time>
   <real_time>true</real_time>
@@ -60,7 +72,7 @@
 
 <!-- Translate / rotate -->
 <plugin filename="TransformControl" name="Transform control">
-  <ignition-gui>
+  <gz-gui>
     <title>Transform control</title>
     <anchors target="3D View">
       <line own="left" target="left"/>
@@ -72,12 +84,12 @@
     <property key="state" type="string">floating</property>
     <property key="showTitleBar" type="bool">false</property>
     <property key="cardBackground" type="string">#03a9f4</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- Insert simple shapes -->
 <plugin filename="Shapes" name="Shapes">
-  <ignition-gui>
+  <gz-gui>
     <anchors target="Transform control">
       <line own="left" target="right"/>
       <line own="top" target="top"/>
@@ -88,7 +100,7 @@
     <property key="state" type="string">floating</property>
     <property key="showTitleBar" type="bool">false</property>
     <property key="cardBackground" type="string">#03a9f4</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- HMI -->

From 3581edb8636d76d151ee792b9027f0bb6e240a6b Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 14:34:22 -0400
Subject: [PATCH 17/29] Update the simulation launch file

---
 turtlebot4_gz_bringup/launch/sim.launch.py | 37 ++++++++++++----------
 1 file changed, 20 insertions(+), 17 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/sim.launch.py b/turtlebot4_gz_bringup/launch/sim.launch.py
index fe23a22..a8e6a06 100644
--- a/turtlebot4_gz_bringup/launch/sim.launch.py
+++ b/turtlebot4_gz_bringup/launch/sim.launch.py
@@ -58,20 +58,24 @@ def generate_launch_description():
     pkg_ros_gz_sim = get_package_share_directory(
         'ros_gz_sim')
 
-    # Set ignition resource path
+     # Set Ignition resource path
     gz_resource_path = SetEnvironmentVariable(
         name='GZ_SIM_RESOURCE_PATH',
-        value=[
-            os.path.join(pkg_turtlebot4_gz_bringup, 'worlds'), ':' +
-            os.path.join(pkg_irobot_create_gz_bringup, 'worlds'), ':' +
-            str(Path(pkg_turtlebot4_description).parent.resolve()), ':' +
-            str(Path(pkg_irobot_create_description).parent.resolve())])
+        value=':'.join([
+            os.path.join(pkg_turtlebot4_gz_bringup, 'worlds'),
+            os.path.join(pkg_irobot_create_gz_bringup, 'worlds'),
+            str(Path(pkg_turtlebot4_description).parent.resolve()),
+            str(Path(pkg_irobot_create_description).parent.resolve())
+        ])
+    )
 
     gz_gui_plugin_path = SetEnvironmentVariable(
         name='GZ_GUI_PLUGIN_PATH',
-        value=[
-            os.path.join(pkg_turtlebot4_gz_gui_plugins, 'lib'), ':' +
-            os.path.join(pkg_irobot_create_gz_plugins, 'lib')])
+        value=":".join([
+            os.path.join(pkg_turtlebot4_gz_gui_plugins, 'lib'),
+            os.path.join(pkg_irobot_create_gz_plugins, 'lib')
+        ])
+    )
 
     # Paths
     gz_sim_launch = PathJoinSubstitution(
@@ -94,18 +98,17 @@ def generate_launch_description():
     )
 
     # Clock bridge
-    # TODO No longer needed in Jazzy?
-#    clock_bridge = Node(package='ros_gz_bridge', executable='parameter_bridge',
-#                        name='clock_bridge',
-#                        output='screen',
-#                        arguments=[
-#                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock'
-#                        ])
+    clock_bridge = Node(package='ros_gz_bridge', executable='parameter_bridge',
+                        name='clock_bridge',
+                        output='screen',
+                        arguments=[
+                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock'
+                        ])
 
     # Create launch description and add actions
     ld = LaunchDescription(ARGUMENTS)
     ld.add_action(gz_resource_path)
     ld.add_action(gz_gui_plugin_path)
     ld.add_action(gazebo)
-#    ld.add_action(clock_bridge)
+    ld.add_action(clock_bridge)
     return ld

From cf212fd7c88edebe4099a1219cfe2c630f6ea5b7 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 14:34:39 -0400
Subject: [PATCH 18/29] ign -> gz for plugin logging, cover up the "UNKNOWN %0"
 text for now

---
 .../Turtlebot4Hmi/Turtlebot4Hmi.cc            |  6 +++---
 .../Turtlebot4Hmi/Turtlebot4Hmi.qml           | 19 ++++++++++++++-----
 2 files changed, 17 insertions(+), 8 deletions(-)

diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
index 524903c..c191f6b 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.cc
@@ -112,7 +112,7 @@ void Turtlebot4Hmi::SetNamespace(const QString &_name)
 {
   this->namespace_ = _name.toStdString();
 
-  ignmsg << "A new robot namespace has been entered: '" <<
+  gzmsg << "A new robot namespace has been entered: '" <<
       this->namespace_ << " ' " <<std::endl;
 
   // Remove existing pub/subs
@@ -145,7 +145,7 @@ void Turtlebot4Hmi::OnHmiButton(const int button)
   button_msg.set_data(button);
 
   if (!this->hmi_button_pub_.Publish(button_msg)) {
-    ignerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
+    gzerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
       this->hmi_button_topic_ << std::endl;
   }
 }
@@ -157,7 +157,7 @@ void Turtlebot4Hmi::OnCreate3Button(const int button)
   button_msg.set_data(button);
 
   if (!this->create3_button_pub_.Publish(button_msg)) {
-    ignerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
+    gzerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
       this->create3_button_topic_ << std::endl;
   }
 }
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
index f511ec6..5bd873b 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
@@ -361,7 +361,7 @@ Rectangle
       id: headerBox
       height: 30
       width: 250
-      color: "transparent"
+      color: "black"
       border.color: "black"
       border.width: 2
       anchors.horizontalCenter: hmiRectangle.horizontalCenter
@@ -369,9 +369,18 @@ Rectangle
       anchors.topMargin: 0
     }
 
+    Label
+    {
+      id: headerLabel
+      anchors.horizontalCenter: headerBox.horizontalCenter
+      anchors.verticalCenter: headerBox.verticalCenter
+      text: qsTr("Actions")
+      color: "white"
+    }
+
     Button {
       id: hmiButton1
-      text: qsTr("1")
+      text: qsTr("Run")
       highlighted: false
       onPressed: { Turtlebot4Hmi.OnHmiButton(1); }
       onReleased: { Turtlebot4Hmi.OnHmiButton(0); }
@@ -393,7 +402,7 @@ Rectangle
 
     Button {
       id: hmiButton2
-      text: qsTr("2")
+      text: qsTr("Top")
       highlighted: false
       onPressed: { Turtlebot4Hmi.OnHmiButton(2); }
       onReleased: { Turtlebot4Hmi.OnHmiButton(0); }
@@ -415,7 +424,7 @@ Rectangle
 
     Button {
       id: hmiButton3
-      text: qsTr("3")
+      text: qsTr("^")
       highlighted: false
       onPressed: { Turtlebot4Hmi.OnHmiButton(3); }
       onReleased: { Turtlebot4Hmi.OnHmiButton(0); }
@@ -437,7 +446,7 @@ Rectangle
 
     Button {
       id: hmiButton4
-      text: qsTr("4")
+      text: qsTr("v")
       highlighted: false
       onPressed: { Turtlebot4Hmi.OnHmiButton(4); }
       onReleased: { Turtlebot4Hmi.OnHmiButton(0); }

From c0e5512ae808b2bdc54a43ea7955531266902925 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 15:09:59 -0400
Subject: [PATCH 19/29] Replace the Table model with CoffeeTable; Table doesn't
 appear to be supported anymore

---
 turtlebot4_gz_bringup/worlds/warehouse.sdf | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_bringup/worlds/warehouse.sdf b/turtlebot4_gz_bringup/worlds/warehouse.sdf
index eb31ad1..707f8a3 100644
--- a/turtlebot4_gz_bringup/worlds/warehouse.sdf
+++ b/turtlebot4_gz_bringup/worlds/warehouse.sdf
@@ -222,7 +222,7 @@
 
     <include>
       <uri>
-        https://fuel.gazebosim.org/1.0/OpenRobotics/models/Table
+        https://fuel.gazebosim.org/1.0/OpenRobotics/models/CoffeeTable
       </uri>
       <name>table0</name>
       <pose>-12.7 6.5 0 0 0 0</pose>

From 168750b302b88a5d856cd74f1fb5cfaedbf168d1 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 15:36:29 -0400
Subject: [PATCH 20/29] Replace the sitting person so they're in a chair
 instead of on the ground

---
 turtlebot4_gz_bringup/worlds/warehouse.sdf | 7 +++----
 1 file changed, 3 insertions(+), 4 deletions(-)

diff --git a/turtlebot4_gz_bringup/worlds/warehouse.sdf b/turtlebot4_gz_bringup/worlds/warehouse.sdf
index 707f8a3..58cda0b 100644
--- a/turtlebot4_gz_bringup/worlds/warehouse.sdf
+++ b/turtlebot4_gz_bringup/worlds/warehouse.sdf
@@ -230,14 +230,13 @@
 
     <!-- People -->
 
-    <!--
     <include>
       <uri>
-      https://fuel.gazebosim.org/1.0/OpenRobotics/models/Rescue Randy Sitting
+      https://fuel.gazebosim.org/1.0/OpenRobotics/models/FemaleVisitorSit
       </uri>
       <name>Person 0 - Sitting</name>
-      <pose>14.65 -10 0 0 0 -1.57</pose>
-    </include> -->
+      <pose>14.3 -4 0 0 -0 -1.43</pose>
+    </include>
 
     <include>
       <uri>

From 6ba8ea590f1059a579ef5c0f35c33d9cdec6f503 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 15:36:55 -0400
Subject: [PATCH 21/29] Hmi -> HMI in titlebars

---
 turtlebot4_gz_bringup/gui/lite/gui.config     | 2 +-
 turtlebot4_gz_bringup/gui/standard/gui.config | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/turtlebot4_gz_bringup/gui/lite/gui.config b/turtlebot4_gz_bringup/gui/lite/gui.config
index 6d2b59e..a9d1935 100644
--- a/turtlebot4_gz_bringup/gui/lite/gui.config
+++ b/turtlebot4_gz_bringup/gui/lite/gui.config
@@ -104,7 +104,7 @@
 </plugin>
 
 <!-- HMI -->
-<plugin filename="Create3Hmi" name="Create3Hmi">
+<plugin filename="Create3Hmi" name="Create3 HMI">
   <ignition-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>
diff --git a/turtlebot4_gz_bringup/gui/standard/gui.config b/turtlebot4_gz_bringup/gui/standard/gui.config
index fc2c77b..cf2e318 100644
--- a/turtlebot4_gz_bringup/gui/standard/gui.config
+++ b/turtlebot4_gz_bringup/gui/standard/gui.config
@@ -104,7 +104,7 @@
 </plugin>
 
 <!-- HMI -->
-<plugin filename="Turtlebot4Hmi" name="Turtlebot4Hmi">
+<plugin filename="Turtlebot4Hmi" name="Turtlebot4 HMI">
   <ignition-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>

From 4dc4e3fb5a5c01eeb3755c0e2dca7e52bddd6529 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 30 Jul 2024 17:33:13 -0400
Subject: [PATCH 22/29] Ignition -> Harmonic transition, minor updates to the
 warehouse world

---
 turtlebot4_gz_bringup/gui/lite/gui.config     |  8 +++----
 turtlebot4_gz_bringup/gui/standard/gui.config |  8 +++----
 .../launch/ros_gz_bridge.launch.py            | 22 +++++++++----------
 turtlebot4_gz_bringup/launch/sim.launch.py    |  6 ++---
 .../launch/turtlebot4_nodes.launch.py         |  2 +-
 .../launch/turtlebot4_spawn.launch.py         |  2 +-
 turtlebot4_gz_bringup/package.xml             |  2 +-
 turtlebot4_gz_bringup/worlds/depot.sdf        | 10 ++++++---
 turtlebot4_gz_bringup/worlds/maze.sdf         | 13 +++++++----
 turtlebot4_gz_bringup/worlds/warehouse.sdf    | 10 ++++++---
 turtlebot4_gz_gui_plugins/CHANGELOG.rst       |  2 +-
 .../Turtlebot4Hmi/CMakeLists.txt              |  2 +-
 .../Turtlebot4Hmi/Turtlebot4Hmi.hh            |  2 +-
 .../Turtlebot4Hmi/Turtlebot4Hmi.qml           |  8 +++----
 turtlebot4_gz_gui_plugins/package.xml         |  2 +-
 turtlebot4_gz_toolbox/CHANGELOG.rst           |  2 +-
 16 files changed, 57 insertions(+), 44 deletions(-)

diff --git a/turtlebot4_gz_bringup/gui/lite/gui.config b/turtlebot4_gz_bringup/gui/lite/gui.config
index a9d1935..583195d 100644
--- a/turtlebot4_gz_bringup/gui/lite/gui.config
+++ b/turtlebot4_gz_bringup/gui/lite/gui.config
@@ -105,20 +105,20 @@
 
 <!-- HMI -->
 <plugin filename="Create3Hmi" name="Create3 HMI">
-  <ignition-gui>
+  <gz-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>
     <property type="double" key="height">200</property>
     <property key="resizable" type="bool">true</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- Teleop -->
 <plugin filename="Teleop">
   <topic>/cmd_vel</topic>
-  <ignition-gui>
+  <gz-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>
     <property key="resizable" type="bool">true</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
diff --git a/turtlebot4_gz_bringup/gui/standard/gui.config b/turtlebot4_gz_bringup/gui/standard/gui.config
index cf2e318..9ff001b 100644
--- a/turtlebot4_gz_bringup/gui/standard/gui.config
+++ b/turtlebot4_gz_bringup/gui/standard/gui.config
@@ -105,20 +105,20 @@
 
 <!-- HMI -->
 <plugin filename="Turtlebot4Hmi" name="Turtlebot4 HMI">
-  <ignition-gui>
+  <gz-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>
     <property type="double" key="height">200</property>
     <property key="resizable" type="bool">true</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
 
 <!-- Teleop -->
 <plugin filename="Teleop">
   <topic>/cmd_vel</topic>
-  <ignition-gui>
+  <gz-gui>
     <property type="bool" key="showTitleBar">true</property>
     <property type="string" key="state">docked</property>
     <property key="resizable" type="bool">true</property>
-  </ignition-gui>
+  </gz-gui>
 </plugin>
diff --git a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
index 479f26b..55d1a1a 100644
--- a/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
+++ b/turtlebot4_gz_bringup/launch/ros_gz_bridge.launch.py
@@ -30,9 +30,9 @@
                           choices=['true', 'false'],
                           description='Use sim time'),
     DeclareLaunchArgument('robot_name', default_value='turtlebot4',
-                          description='Ignition model name'),
+                          description='Gazebo model name'),
     DeclareLaunchArgument('dock_name', default_value='standard_dock',
-                          description='Ignition model name'),
+                          description='Gazebo model name'),
     DeclareLaunchArgument('namespace', default_value='',
                           description='Robot namespace'),
     DeclareLaunchArgument('world', default_value='warehouse',
@@ -89,7 +89,7 @@ def generate_launch_description():
             ['/world/', world,
              '/model/', robot_name,
              '/link/rplidar_link/sensor/rplidar/scan' +
-             '@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan']
+             '@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan']
         ],
         remappings=[
             (['/world/', world,
@@ -108,10 +108,10 @@ def generate_launch_description():
         arguments=[
             [namespace, '/hmi/display/raw' +
              '@std_msgs/msg/String' +
-             ']ignition.msgs.StringMsg'],
+             ']gz.msgs.StringMsg'],
             [namespace, '/hmi/display/selected' +
              '@std_msgs/msg/Int32' +
-             ']ignition.msgs.Int32']
+             ']gz.msgs.Int32']
         ],
         remappings=[
             ([namespace, '/hmi/display/raw'],
@@ -131,7 +131,7 @@ def generate_launch_description():
         arguments=[
             [namespace, '/hmi/buttons' +
              '@std_msgs/msg/Int32' +
-             '[ignition.msgs.Int32']
+             '[gz.msgs.Int32']
         ],
         remappings=[
             ([namespace, '/hmi/buttons'],
@@ -149,7 +149,7 @@ def generate_launch_description():
         arguments=[
             [namespace, '/hmi/led/' + led +
              '@std_msgs/msg/Int32' +
-             ']ignition.msgs.Int32'] for led in leds
+             ']gz.msgs.Int32'] for led in leds
         ],
         remappings=[
             ([namespace, '/hmi/led/' + led],
@@ -169,22 +169,22 @@ def generate_launch_description():
              '/model/', robot_name,
              '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image' +
              '@sensor_msgs/msg/Image' +
-             '[ignition.msgs.Image'],
+             '[gz.msgs.Image'],
             ['/world/', world,
              '/model/', robot_name,
              '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image' +
              '@sensor_msgs/msg/Image' +
-             '[ignition.msgs.Image'],
+             '[gz.msgs.Image'],
             ['/world/', world,
              '/model/', robot_name,
              '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points' +
              '@sensor_msgs/msg/PointCloud2' +
-             '[ignition.msgs.PointCloudPacked'],
+             '[gz.msgs.PointCloudPacked'],
             ['/world/', world,
              '/model/', robot_name,
              '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info' +
              '@sensor_msgs/msg/CameraInfo' +
-             '[ignition.msgs.CameraInfo'],
+             '[gz.msgs.CameraInfo'],
             ],
         remappings=[
             (['/world/', world,
diff --git a/turtlebot4_gz_bringup/launch/sim.launch.py b/turtlebot4_gz_bringup/launch/sim.launch.py
index a8e6a06..0b8c848 100644
--- a/turtlebot4_gz_bringup/launch/sim.launch.py
+++ b/turtlebot4_gz_bringup/launch/sim.launch.py
@@ -58,7 +58,7 @@ def generate_launch_description():
     pkg_ros_gz_sim = get_package_share_directory(
         'ros_gz_sim')
 
-     # Set Ignition resource path
+     # Set Gazebo resource path
     gz_resource_path = SetEnvironmentVariable(
         name='GZ_SIM_RESOURCE_PATH',
         value=':'.join([
@@ -81,7 +81,7 @@ def generate_launch_description():
     gz_sim_launch = PathJoinSubstitution(
         [pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'])
 
-    # Ignition gazebo
+    # Gazebo harmonic
     gazebo = IncludeLaunchDescription(
         PythonLaunchDescriptionSource([gz_sim_launch]),
         launch_arguments=[
@@ -102,7 +102,7 @@ def generate_launch_description():
                         name='clock_bridge',
                         output='screen',
                         arguments=[
-                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock'
+                            '/clock' + '@rosgraph_msgs/msg/Clock' + '[gz.msgs.Clock'
                         ])
 
     # Create launch description and add actions
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
index 4388478..37b7937 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_nodes.launch.py
@@ -54,7 +54,7 @@ def generate_launch_description():
         output='screen',
     )
 
-    # Turtlebot4 Ignition Hmi node
+    # Turtlebot4 Gazebo Hmi node
     turtlebot4_gz_hmi_node = Node(
         package='turtlebot4_gz_toolbox',
         name='turtlebot4_gz_hmi_node',
diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index d1b08a8..c0e2b53 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -192,7 +192,7 @@ def generate_launch_description():
             ]
         ),
 
-        # Create 3 Ignition nodes
+        # Create 3 Gazebo nodes
         IncludeLaunchDescription(
             PythonLaunchDescriptionSource([create3_gz_nodes_launch]),
             launch_arguments=[
diff --git a/turtlebot4_gz_bringup/package.xml b/turtlebot4_gz_bringup/package.xml
index f929021..061dc8b 100644
--- a/turtlebot4_gz_bringup/package.xml
+++ b/turtlebot4_gz_bringup/package.xml
@@ -3,7 +3,7 @@
 <package format="3">
   <name>turtlebot4_gz_bringup</name>
   <version>1.0.2</version>
-  <description>TurtleBot 4 Ignition Simulator bringup</description>
+  <description>TurtleBot 4 Gazebo Simulator bringup</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
   <license>Apache 2.0</license>
 
diff --git a/turtlebot4_gz_bringup/worlds/depot.sdf b/turtlebot4_gz_bringup/worlds/depot.sdf
index c7f04c0..24f9a88 100644
--- a/turtlebot4_gz_bringup/worlds/depot.sdf
+++ b/turtlebot4_gz_bringup/worlds/depot.sdf
@@ -8,9 +8,13 @@
       <max_step_size>0.003</max_step_size>
       <real_time_factor>1.0</real_time_factor>
     </physics>
-    <plugin filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"></plugin>
-    <plugin filename="ignition-gazebo-user-commands-system" name="ignition::gazebo::systems::UserCommands"></plugin>
-    <plugin filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"></plugin>
+    <plugin name="gz::sim::systems::Physics" filename="gz-sim-physics-system" />
+    <plugin name="gz::sim::systems::UserCommands" filename="gz-sim-user-commands-system" />
+    <plugin name="gz::sim::systems::SceneBroadcaster" filename="gz-sim-scene-broadcaster-system" />
+    <plugin name="gz::sim::systems::Contact" filename="gz-sim-contact-system" />
+    <!--<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
+        <render_engine>ogre2</render_engine>
+    </plugin>-->
 
     <include>
       <uri>
diff --git a/turtlebot4_gz_bringup/worlds/maze.sdf b/turtlebot4_gz_bringup/worlds/maze.sdf
index 00950da..61e1345 100644
--- a/turtlebot4_gz_bringup/worlds/maze.sdf
+++ b/turtlebot4_gz_bringup/worlds/maze.sdf
@@ -6,10 +6,15 @@
             <real_time_factor>1</real_time_factor>
             <real_time_update_rate>1000</real_time_update_rate>
         </physics>
-        <plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system' />
-        <plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system' />
-        <plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system' />
-        <plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system' />
+
+        <plugin name="gz::sim::systems::Physics" filename="gz-sim-physics-system" />
+        <plugin name="gz::sim::systems::UserCommands" filename="gz-sim-user-commands-system" />
+        <plugin name="gz::sim::systems::SceneBroadcaster" filename="gz-sim-scene-broadcaster-system" />
+        <plugin name="gz::sim::systems::Contact" filename="gz-sim-contact-system" />
+        <!--<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
+            <render_engine>ogre2</render_engine>
+        </plugin>-->
+
         <light name='sun' type='directional'>
             <cast_shadows>1</cast_shadows>
             <pose>0 0 10 0 -0 0</pose>
diff --git a/turtlebot4_gz_bringup/worlds/warehouse.sdf b/turtlebot4_gz_bringup/worlds/warehouse.sdf
index 58cda0b..c818bd2 100644
--- a/turtlebot4_gz_bringup/worlds/warehouse.sdf
+++ b/turtlebot4_gz_bringup/worlds/warehouse.sdf
@@ -5,9 +5,13 @@
       <max_step_size>0.003</max_step_size>
       <real_time_factor>1.0</real_time_factor>
     </physics>
-    <plugin name='ignition::gazebo::systems::Physics' filename='libignition-gazebo-physics-system.so'/>
-    <plugin name='ignition::gazebo::systems::UserCommands' filename='libignition-gazebo-user-commands-system.so'/>
-    <plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='libignition-gazebo-scene-broadcaster-system.so'/>
+    <plugin name="gz::sim::systems::Physics" filename="gz-sim-physics-system" />
+    <plugin name="gz::sim::systems::UserCommands" filename="gz-sim-user-commands-system" />
+    <plugin name="gz::sim::systems::SceneBroadcaster" filename="gz-sim-scene-broadcaster-system" />
+    <plugin name="gz::sim::systems::Contact" filename="gz-sim-contact-system" />
+    <!--<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
+        <render_engine>ogre2</render_engine>
+    </plugin>-->
 
     <scene>
       <ambient>1 1 1 1</ambient>
diff --git a/turtlebot4_gz_gui_plugins/CHANGELOG.rst b/turtlebot4_gz_gui_plugins/CHANGELOG.rst
index 7b77656..e184e0f 100644
--- a/turtlebot4_gz_gui_plugins/CHANGELOG.rst
+++ b/turtlebot4_gz_gui_plugins/CHANGELOG.rst
@@ -1,5 +1,5 @@
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package turtlebot4_ignition_gui_plugins
+Changelog for package turtlebot4_gz_gui_plugins
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
 1.0.2 (2024-04-15)
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
index 5014d8e..29b8bce 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/CMakeLists.txt
@@ -16,7 +16,7 @@ find_package(Qt5
   REQUIRED
 )
 
-# Find the Ignition gui library
+# Find the Gz gui library
 find_package(gz-gui8 REQUIRED)
 find_package(gz-common5 REQUIRED)
 
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
index db26b10..e518995 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
@@ -50,7 +50,7 @@ public:
   Turtlebot4Hmi();
   /// \brief Destructor
   virtual ~Turtlebot4Hmi();
-  /// \brief Called by Ignition GUI when plugin is instantiated.
+  /// \brief Called by Gz GUI when plugin is instantiated.
   /// \param[in] _pluginElem XML configuration for this plugin.
   void LoadConfig(const tinyxml2::XMLElement * _pluginElem) override;
   // \brief Get the robot namespace as a string, for example
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
index 5bd873b..7fdc610 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.qml
@@ -394,7 +394,7 @@ Rectangle
         implicitHeight: 40
         opacity: 0.3
         border.color: "#000000"
-        border.width: control.down ? 2 : 1
+        border.width: 1
         radius: 20
         color: "gray"
       }
@@ -416,7 +416,7 @@ Rectangle
         implicitHeight: 40
         opacity: 0.3
         border.color: "#000000"
-        border.width: control.down ? 2 : 1
+        border.width: 1
         radius: 20
         color: "gray"
       }
@@ -438,7 +438,7 @@ Rectangle
         implicitHeight: 40
         opacity: 0.3
         border.color: "#000000"
-        border.width: control.down ? 2 : 1
+        border.width: 1
         radius: 20
         color: "gray"
       }
@@ -460,7 +460,7 @@ Rectangle
         implicitHeight: 40
         opacity: 0.3
         border.color: "#000000"
-        border.width: control.down ? 2 : 1
+        border.width: 1
         radius: 20
         color: "gray"
       }
diff --git a/turtlebot4_gz_gui_plugins/package.xml b/turtlebot4_gz_gui_plugins/package.xml
index 2c5590e..22f04e3 100644
--- a/turtlebot4_gz_gui_plugins/package.xml
+++ b/turtlebot4_gz_gui_plugins/package.xml
@@ -3,7 +3,7 @@
 <package format="3">
   <name>turtlebot4_gz_gui_plugins</name>
   <version>1.0.2</version>
-  <description>Turtlebot4 Ignition Simulator GUI Plugins</description>
+  <description>Turtlebot4 Gazebo Simulator GUI Plugins</description>
   <maintainer email="rkreinin@clearpathrobotics.com">rkreinin</maintainer>
   <license>Apache 2.0</license>
 
diff --git a/turtlebot4_gz_toolbox/CHANGELOG.rst b/turtlebot4_gz_toolbox/CHANGELOG.rst
index 911fa63..ad120ef 100644
--- a/turtlebot4_gz_toolbox/CHANGELOG.rst
+++ b/turtlebot4_gz_toolbox/CHANGELOG.rst
@@ -1,5 +1,5 @@
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package turtlebot4_ignition_toolbox
+Changelog for package turtlebot4_gz_toolbox
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
 1.0.2 (2024-04-15)

From 16096c356a59805d9fb67b7c8d54e27256a5e7e3 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 31 Jul 2024 17:20:51 -0400
Subject: [PATCH 23/29] Fix gz-gui8 rosdep

---
 turtlebot4_gz_gui_plugins/package.xml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_gui_plugins/package.xml b/turtlebot4_gz_gui_plugins/package.xml
index 22f04e3..68388c3 100644
--- a/turtlebot4_gz_gui_plugins/package.xml
+++ b/turtlebot4_gz_gui_plugins/package.xml
@@ -8,7 +8,7 @@
   <license>Apache 2.0</license>
 
   <buildtool_depend>ament_cmake</buildtool_depend>
-  <buildtool_depend>gz-gui8</buildtool_depend>
+  <buildtool_depend>gz_gui_vendor</buildtool_depend>
   <depend>qml-module-qtquick-extras</depend>
 
   <test_depend>ament_lint_auto</test_depend>

From c1d627f8b8f9ddb5b73ebdce16c140e729ec962f Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 21 Aug 2024 14:53:42 -0400
Subject: [PATCH 24/29] Launch Rviz in the naviation profile if it's being
 started as part of the simulation launch

---
 turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
index c0e2b53..f9dc65a 100644
--- a/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
+++ b/turtlebot4_gz_bringup/launch/turtlebot4_spawn.launch.py
@@ -77,7 +77,7 @@ def generate_launch_description():
     turtlebot4_ros_gz_bridge_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'ros_gz_bridge.launch.py'])
     rviz_launch = PathJoinSubstitution(
-        [pkg_turtlebot4_viz, 'launch', 'view_robot.launch.py'])
+        [pkg_turtlebot4_viz, 'launch', 'view_navigation.launch.py'])
     turtlebot4_node_launch = PathJoinSubstitution(
         [pkg_turtlebot4_gz_bringup, 'launch', 'turtlebot4_nodes.launch.py'])
     create3_nodes_launch = PathJoinSubstitution(

From efefbdea5a7ae56f30cdee6f93c520ff04d53a23 Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Wed, 21 Aug 2024 15:06:15 -0400
Subject: [PATCH 25/29] Update CI for Jazzy

---
 .github/workflows/ci.yml | 10 +++++-----
 1 file changed, 5 insertions(+), 5 deletions(-)

diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index b2a431b..f8d71c4 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -3,18 +3,18 @@ name: turtlebot4_simulator_ci
 on: [push, pull_request]
 
 jobs:
-  turtlebot4_humble_ci:
-    name: Humble
-    runs-on: ubuntu-22.04
+  turtlebot4_jazzy_ci:
+    name: Jazzy
+    runs-on: ubuntu-24.04
     steps:
       - uses: actions/checkout@v2.3.4
       - uses: ros-tooling/setup-ros@v0.7
         with:
-          required-ros-distributions: humble
+          required-ros-distributions: jazzy
       - uses: ros-tooling/action-ros-ci@v0.3
         id: action_ros_ci_step
         with:
-          target-ros2-distro: humble
+          target-ros2-distro: jazzy
           import-token: ${{ secrets.GITHUB_TOKEN }}
           package-name:
             turtlebot4_gz_bringup

From 6a286e352721ebd89f2abdb06d394fbb5142665d Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 27 Aug 2024 12:03:33 -0400
Subject: [PATCH 26/29] Change the gz_gui_vendor dependency to depend (from
 buildtool_depend)

---
 turtlebot4_gz_gui_plugins/package.xml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/turtlebot4_gz_gui_plugins/package.xml b/turtlebot4_gz_gui_plugins/package.xml
index 68388c3..112541b 100644
--- a/turtlebot4_gz_gui_plugins/package.xml
+++ b/turtlebot4_gz_gui_plugins/package.xml
@@ -8,7 +8,7 @@
   <license>Apache 2.0</license>
 
   <buildtool_depend>ament_cmake</buildtool_depend>
-  <buildtool_depend>gz_gui_vendor</buildtool_depend>
+  <depend>gz_gui_vendor</depend>
   <depend>qml-module-qtquick-extras</depend>
 
   <test_depend>ament_lint_auto</test_depend>

From e57cc4ec90125c725db97fe80ea2f829034dbdff Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 27 Aug 2024 12:07:22 -0400
Subject: [PATCH 27/29] Update github issue template

---
 .github/ISSUE_TEMPLATE/1-bug.yml | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/.github/ISSUE_TEMPLATE/1-bug.yml b/.github/ISSUE_TEMPLATE/1-bug.yml
index e1d2ea5..e80731e 100644
--- a/.github/ISSUE_TEMPLATE/1-bug.yml
+++ b/.github/ISSUE_TEMPLATE/1-bug.yml
@@ -30,6 +30,7 @@ body:
         - Select One
         - Galactic
         - Humble
+        - Jazzy
     validations:
       required: true
   - type: dropdown
@@ -52,6 +53,7 @@ body:
         - Select One
         - Ubuntu 20.04
         - Ubuntu 22.04
+        - Ubuntu 24.04
         - Other Linux
         - Windows / MAC
     validations:

From d643e35791a026f8e3ac682fffe10074fa1cecbf Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 3 Sep 2024 11:42:32 -0400
Subject: [PATCH 28/29] Enable OSRF testing packages for CI

---
 .github/workflows/ci.yml | 1 +
 1 file changed, 1 insertion(+)

diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index f8d71c4..db88d0a 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -11,6 +11,7 @@ jobs:
       - uses: ros-tooling/setup-ros@v0.7
         with:
           required-ros-distributions: jazzy
+          use-ros2-testing: true
       - uses: ros-tooling/action-ros-ci@v0.3
         id: action_ros_ci_step
         with:

From 56c1b797cd2fce6938bd8d30b9a90da14327511a Mon Sep 17 00:00:00 2001
From: Chris Iverach-Brereton <civerachb@clearpathrobotics.com>
Date: Tue, 3 Sep 2024 11:42:50 -0400
Subject: [PATCH 29/29] Linting & formatting fixes

---
 turtlebot4_gz_bringup/launch/sim.launch.py    | 25 +++++++++++--------
 .../Turtlebot4Hmi/Turtlebot4Hmi.hh            |  4 +--
 2 files changed, 16 insertions(+), 13 deletions(-)

diff --git a/turtlebot4_gz_bringup/launch/sim.launch.py b/turtlebot4_gz_bringup/launch/sim.launch.py
index 0b8c848..7b4c665 100644
--- a/turtlebot4_gz_bringup/launch/sim.launch.py
+++ b/turtlebot4_gz_bringup/launch/sim.launch.py
@@ -58,7 +58,7 @@ def generate_launch_description():
     pkg_ros_gz_sim = get_package_share_directory(
         'ros_gz_sim')
 
-     # Set Gazebo resource path
+    # Set Gazebo resource path
     gz_resource_path = SetEnvironmentVariable(
         name='GZ_SIM_RESOURCE_PATH',
         value=':'.join([
@@ -71,7 +71,7 @@ def generate_launch_description():
 
     gz_gui_plugin_path = SetEnvironmentVariable(
         name='GZ_GUI_PLUGIN_PATH',
-        value=":".join([
+        value=':'.join([
             os.path.join(pkg_turtlebot4_gz_gui_plugins, 'lib'),
             os.path.join(pkg_irobot_create_gz_plugins, 'lib')
         ])
@@ -85,15 +85,18 @@ def generate_launch_description():
     gazebo = IncludeLaunchDescription(
         PythonLaunchDescriptionSource([gz_sim_launch]),
         launch_arguments=[
-            ('gz_args', [LaunchConfiguration('world'),
-                          '.sdf',
-                          ' -v 4',
-                          ' --gui-config ',
-                          PathJoinSubstitution(
-                            [pkg_turtlebot4_gz_bringup,
-                             'gui',
-                             LaunchConfiguration('model'),
-                             'gui.config'])])
+            ('gz_args', [
+                LaunchConfiguration('world'),
+                '.sdf',
+                ' -v 4',
+                ' --gui-config ',
+                PathJoinSubstitution([
+                    pkg_turtlebot4_gz_bringup,
+                    'gui',
+                    LaunchConfiguration('model'),
+                    'gui.config'
+                ])
+            ])
         ]
     )
 
diff --git a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
index e518995..b3ad5a0 100644
--- a/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
+++ b/turtlebot4_gz_gui_plugins/Turtlebot4Hmi/Turtlebot4Hmi.hh
@@ -20,12 +20,12 @@
 #define TURTLEBOT4_GZ_GUI_PLUGINS__TURTLEBOT4HMI__TURTLEBOT4HMI_HH_
 
 #include <gz/gui/qt.h>
-#include <gz/msgs.hh>
 
 #include <string>
 
-#include <gz/transport/Node.hh>
 #include <gz/gui/Plugin.hh>
+#include <gz/msgs.hh>
+#include <gz/transport/Node.hh>
 
 namespace gz
 {