` tag with comments describing the mapping
+from the original plugin.
+
+```xml
+
+ joint_states
+ wheel_left_joint
+ wheel_right_joint
+
+```
+
+### World plugins
+
+As mentioned earlier, sensors are handled by generic world level plugins.
+
+
+ By default, if there are no world plugins specified, Gazebo adds the Physics,
+ SceneBroadcaster, and UserCommands plugins. However, if we specify any
+ plugins at all, Gazebo will assume we want to override the defaults, so will not
+ add any default plugins.
+
+
+Therefore, we have to add the additional plugins for IMU and Lidar sensors as
+well as the ones that would have been added by default. We will once again edit
+`turtlebot3_gazebo/worlds/empty_world.world` add the following right after
+``.
+
+```xml
+
+
+
+
+
+
+
+ ogre2
+
+
+
+```
+
+## Bridge ROS topics
+
+In Gazebo Classic, communication with ROS is enabled by plugins in
+`gazebo_ros_pkgs` that directly interface with the simulator. In contrast, in
+the new Gazebo, communication with ROS is mainly done through topic bridges
+provided by `ros_gz`. The bridge node is a generic node that bridges topics
+between `gz-transport` and ROS 2.
+
+To create the bridge, we'll use a `yaml` file that contains the topic names and
+their mappings. We'll add a new directory `params` in `turtlebot3_gazebo` and
+create `turtlebot3_waffle_bridge.yaml` with the following content:
+
+```yaml
+# gz topic published by the simulator core
+- ros_topic_name: "clock"
+ gz_topic_name: "clock"
+ ros_type_name: "rosgraph_msgs/msg/Clock"
+ gz_type_name: "gz.msgs.Clock"
+ direction: GZ_TO_ROS
+
+# gz topic published by JointState plugin
+- ros_topic_name: "joint_states"
+ gz_topic_name: "joint_states"
+ ros_type_name: "sensor_msgs/msg/JointState"
+ gz_type_name: "gz.msgs.Model"
+ direction: GZ_TO_ROS
+
+# gz topic published by DiffDrive plugin
+- ros_topic_name: "odom"
+ gz_topic_name: "odom"
+ ros_type_name: "nav_msgs/msg/Odometry"
+ gz_type_name: "gz.msgs.Odometry"
+ direction: GZ_TO_ROS
+
+# gz topic published by DiffDrive plugin
+- ros_topic_name: "tf"
+ gz_topic_name: "tf"
+ ros_type_name: "tf2_msgs/msg/TFMessage"
+ gz_type_name: "gz.msgs.Pose_V"
+ direction: GZ_TO_ROS
+
+# gz topic subscribed to by DiffDrive plugin
+- ros_topic_name: "cmd_vel"
+ gz_topic_name: "cmd_vel"
+ ros_type_name: "geometry_msgs/msg/Twist"
+ gz_type_name: "gz.msgs.Twist"
+ direction: ROS_TO_GZ
+
+# gz topic published by IMU plugin
+- ros_topic_name: "imu"
+ gz_topic_name: "imu"
+ ros_type_name: "sensor_msgs/msg/Imu"
+ gz_type_name: "gz.msgs.IMU"
+ direction: GZ_TO_ROS
+
+# gz topic published by Sensors plugin
+- ros_topic_name: "scan"
+ gz_topic_name: "scan"
+ ros_type_name: "sensor_msgs/msg/LaserScan"
+ gz_type_name: "gz.msgs.LaserScan"
+ direction: GZ_TO_ROS
+
+# gz topic published by Sensors plugin (Camera)
+- ros_topic_name: "camera/camera_info"
+ gz_topic_name: "camera/camera_info"
+ ros_type_name: "sensor_msgs/msg/CameraInfo"
+ gz_type_name: "gz.msgs.CameraInfo"
+ direction: GZ_TO_ROS
+```
+
+[The completed yaml file can be found here.](https://github.com/azeey/turtlebot3_simulations/blob/new_gazebo/turtlebot3_gazebo/params/turtlebot3_waffle_bridge.yaml)
+Each entry in the yaml file has a ROS topic name, a Gazebo topic name, a ROS
+data/message type, and a direction which indicates which way messages flow. We
+will need to update the
+[`CMakeLists.txt`](https://github.com/azeey/turtlebot3_simulations/blob/ccb2385fd478e79c898d290d80fa41f35b1bbb83/turtlebot3_gazebo/CMakeLists.txt#L72)
+file to install the new `params` directory we created. The CMake `install`
+command should look like
+
+```cmake
+install(DIRECTORY launch models params rviz urdf worlds
+ DESTINATION share/${PROJECT_NAME}/
+)
+```
+
+Finally, we will edit
+[`turtlebot3_gazebo/launch/spawn_turtlebot3.launch.py`](https://github.com/ROBOTIS-GIT/turtlebot3_simulations//blob/d16cdbe7ecd601ccad48f87f77b6d89079ec5ac1/turtlebot3_gazebo/launch/spawn_turtlebot3.launch.py),
+to create the bridge node:
+
+```python
+bridge_params = os.path.join(
+ get_package_share_directory('turtlebot3_gazebo'),
+ 'params',
+ 'turtlebot3_waffle_bridge.yaml'
+)
+
+start_gazebo_ros_bridge_cmd = Node(
+ package='ros_gz_bridge',
+ executable='parameter_bridge',
+ arguments=[
+ '--ros-args',
+ '-p',
+ f'config_file:={bridge_params}',
+ ],
+ output='screen',
+)
+```
+
+You might have noticed that in the bridge parameters, we did not include the
+`camera/image_raw` topic. While it is possible to bridge the image topic in a
+similar manner as all the other topics, we will make use of a specialized bridge
+node,
+[`ros_gz_image`](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_image),
+which provides a much more efficient bridge for image topics. We'll add the
+following snippet to `turtlebot3_gazebo/launch/spawn_turtlebot3.launch.py`:
+
+```python
+start_gazebo_ros_image_bridge_cmd = Node(
+ package='ros_gz_image',
+ executable='image_bridge',
+ arguments=['/camera/image_raw'],
+ output='screen',
+)
+```
+
+Finally, we will add all new the actions to the list of `LaunchDescription`s
+returned by the `generate_launch_description` function
+
+```python
+# ...
+
+# Add the action to `ld` toward the end of the file
+
+ld.add_action(start_gazebo_ros_bridge_cmd)
+ld.add_action(start_gazebo_ros_image_bridge_cmd)
+
+```
+
+You can find the
+[Gazebo Classic `spawn_turtlebot3.launch.py` file here](https://github.com/ROBOTIS-GIT/turtlebot3_simulations/blob/d16cdbe7ecd601ccad48f87f77b6d89079ec5ac1/turtlebot3_gazebo/launch/spawn_turtlebot3.launch.py),
+and the
+[updated Gazebo `spawn_turtlebot3.launch.py` file here](https://github.com/azeey/turtlebot3_simulations/blob/new_gazebo/turtlebot3_gazebo/launch/spawn_turtlebot3.launch.py).
+
+We are now ready to launch the empty world which spawns the waffle robot and
+sets up the bridge so that we can communicate with it from ROS 2.
+
+```bash
+export TURTLEBOT3_MODEL=waffle
+ros2 launch turtlebot3_gazebo empty_world.launch.py
+```
+
+Here's a screenshot of Turtlebot3 running in Gazebo obtained by launching
+`empty_world.launch.py`. The Lidar visualization is enabled by adding the
+"Visualize Lidar" GUI plugin (see
+[tutorial](https://gazebosim.org/docs/fortress/gui) on how to add GUI plugins).
+
+![Screenshot of turtlebot 3 running in Gazebo](images/gz_ros2_migration/gazebo_turtlebot3.png)
+
+It is also now possible to do the
+[SLAM](https://emanual.robotis.com/docs/en/platform/turtlebot3/slam_simulation/)
+and
+[Navigation](https://emanual.robotis.com/docs/en/platform/turtlebot3/nav_simulation/)
+tutorials from the Turtlebot3 manual (make sure to select the Humble tab).
+However, it requires updating `turtlebot3_world.world` and
+`turtlebot3_world.launch.py` files according what we've discussed in this
+tutorial. For reference, those files have also been migrated in
+[this fork](https://github.com/azeey/turtlebot3_simulations/tree/new_gazebo).
+
+## Migrating other files in turtlebot3_gazebo
+
+This tutorial does not cover all aspects of migrating models and launch files
+from Gazebo classic. The following is a list of useful resources that cover
+other aspects, such as migrating Gazebo Classic plugins, materials and textures.
+
+- Migration from Gazebo Classic: Plugins -
+ [Fortress](https://gazebosim.org/api/gazebo/6/migrationplugins.html) |
+ [Harmonic](https://gazebosim.org/api/sim/8/migrationplugins.html)
+- Migration from Gazebo classic: SDF -
+ [Fortress](https://gazebosim.org/api/gazebo/6/migrationsdf.html) |
+ [Harmonic](https://gazebosim.org/api/sim/8/migrationsdf.html)
+- Case study: migrating the ArduPilot ModelPlugin from Gazebo classic to
+ Gazebo - [Fortress](https://gazebosim.org/api/gazebo/6/ardupilot.html) |
+ [Harmonic](https://gazebosim.org/api/sim/8/ardupilot.html)
+- [Basic description of SDF worlds](https://gazebosim.org/docs/latest/sdf_worlds)
+- [Feature Comparison with Gazebo Classic](https://gazebosim.org/docs/latest/comparison)
+- [Documentation for ros_gz](https://gazebosim.org/docs/latest/ros2_integration)
+- List of Systems (plugins):
+ [Fortress](https://gazebosim.org/api/gazebo/6/namespaceignition_1_1gazebo_1_1systems.html)
+ |
+ [Harmonic](https://gazebosim.org/api/sim/8/namespacegz_1_1sim_1_1systems.html)