Skip to content

Commit

Permalink
Updates to getting started / build for modern GZ (#607)
Browse files Browse the repository at this point in the history
* Updates to getting started / build for modern GZ

Signed-off-by: Steve Macenski <[email protected]>

* fixing format problems

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
  • Loading branch information
SteveMacenski authored Nov 19, 2024
1 parent b15785f commit 9fcbec1
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 16 deletions.
16 changes: 16 additions & 0 deletions development_guides/build_docs/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,13 @@ Build and Install
Install
*******


Nav2 and its dependencies are released as binaries.
You may install it via the following to get the latest stable released version:

For Iron and Older
==================

.. code:: bash
source /opt/ros/<distro>/setup.bash
Expand All @@ -17,6 +21,17 @@ You may install it via the following to get the latest stable released version:
ros-$ROS_DISTRO-nav2-bringup \
ros-$ROS_DISTRO-turtlebot3*
For Jazzy and Newer
===================

.. code:: bash
source /opt/ros/<distro>/setup.bash
sudo apt install \
ros-$ROS_DISTRO-navigation2 \
ros-$ROS_DISTRO-nav2-bringup \
ros-$ROS_DISTRO-nav2-minimal-tb*
Build
*****

Expand Down Expand Up @@ -91,6 +106,7 @@ Once your environment is setup, clone the repo and build the workspace:
source <ros_ws>/install/setup.bash
mkdir -p ~/nav2_ws/src && cd ~/nav2_ws
git clone https://github.com/ros-navigation/navigation2.git --branch main ./src/navigation2
git clone https://github.com/ros-navigation/nav2_minimal_turtlebot_simulation.git --branch main ./src/nav2_minimal_turtlebot_simulation
rosdep install -r -y \
--from-paths ./src \
--ignore-src
Expand Down
30 changes: 18 additions & 12 deletions getting_started/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@ and navigating a simulated Turtlebot 3 in the Gazebo simulator.
Installation
************

Jazzy introduced the new Gazebo modern simulator, replacing Gazebo Classic.
Thus, for Jazzy and newer, the installation packages and instructions are slightly different to pull in the appropriate packages.

1. Install the `ROS 2 binary packages`_ as described in the official docs
2. Install the |PN| packages using your operating system's package manager:

Expand All @@ -28,7 +31,16 @@ Installation
sudo apt install ros-<ros2-distro>-navigation2
sudo apt install ros-<ros2-distro>-nav2-bringup
3. Install the Turtlebot 3 packages (Humble and older):
3. Install the demo robot (Turtlebot) for gazebo:

For **Jazzy and newer**, install the Turtlebot 3 & 4 packages for Gazebo Modern. It should be automatically installed with ``nav2_bringup``:

.. code-block:: bash
sudo apt install ros-<ros2-distro>-nav2-minimal-tb*
For **Iron and older**, install Turtlebot 3 packages for gazebo classic:

.. code-block:: bash
Expand All @@ -38,13 +50,13 @@ Running the Example
*******************

1. Start a terminal in your GUI
2. Set key environment variables:
2. Set key environment variables, some of which are only required for Iron and older:

.. code-block:: bash
source /opt/ros/<ros2-distro>/setup.bash
export TURTLEBOT3_MODEL=waffle
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/opt/ros/<ros2-distro>/share/turtlebot3_gazebo/models
export TURTLEBOT3_MODEL=waffle # Iron and older only with Gazebo Classic
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/opt/ros/<ros2-distro>/share/turtlebot3_gazebo/models # Iron and older only with Gazebo Classic
3. In the same terminal, run:

Expand All @@ -53,22 +65,16 @@ Running the Example
ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False
.. note::

For ``ROS 2 Dashing Diademata`` or earlier, use
``nav2_simulation_launch.py``.
However, it is recommended to use the most recent `ROS 2 LTS distribution
<https://ros.org/reps/rep-2000.html>`_ for improved stability and feature
completeness.

``headless`` defaults to true; if not set to false, gzclient (the 3d view) is not started.

This launch file will launch Nav2 with the AMCL localizer in the
``turtlebot3_world`` world.
simulation world.
It will also launch the robot state publisher to provide transforms,
a Gazebo instance with the Turtlebot3 URDF, and RVIZ.

If everything has started correctly, you will see the RViz and Gazebo GUIs like
this:
this (this is Gazebo Classic, but what you see with modern Gazebo is virtually identical):

.. image:: /images/rviz/rviz-not-started.png
:width: 45%
Expand Down
8 changes: 7 additions & 1 deletion setup_guides/odom/setup_odom.rst
Original file line number Diff line number Diff line change
@@ -1,7 +1,13 @@
Setting Up Odometry
###################

In this guide, we will be looking at how to integrate our robot's odometry system with Nav2. First we will provide a brief introduction on odometry, plus the necessary messages and transforms that need to be published for Nav2 to function correctly. Next, we will show how to setup odometry with two different cases. In the first case, we will show how to setup an odometry system for a robot with already available wheel encoders. In the second case, we will build a demo that simulates a functioning odometry system on ``sam_bot`` (the robot that we built in the previous section) using Gazebo. Afterwards, we will discuss how various sources of odometry can be fused to provide a smoothed odometry using the ``robot_localization`` package. Lastly, we will also show how to publish the ``odom`` => ``base_link`` transform using ``robot_localization``.
In this guide, we will be looking at how to integrate our robot's odometry system with Nav2.
First we will provide a brief introduction on odometry, plus the necessary messages and transforms that need to be published for Nav2 to function correctly.
Next, we will show how to setup odometry with two different cases.
In the first case, we will show how to setup an odometry system for a robot with already available wheel encoders.
In the second case, we will build a demo that simulates a functioning odometry system on ``sam_bot`` (the robot that we built in the previous section) using Gazebo.
Afterwards, we will discuss how various sources of odometry can be fused to provide a smoothed odometry using the ``robot_localization`` package.
Lastly, we will also show how to publish the ``odom`` => ``base_link`` transform using ``robot_localization``.

.. seealso::
The complete source code in this tutorial can be found in `navigation2_tutorials <https://github.com/ros-navigation/navigation2_tutorials/tree/master/sam_bot_description>`_ repository under the ``sam_bot_description`` package. Note that the repository contains the full code after accomplishing all the tutorials in this guide.
Expand Down
8 changes: 7 additions & 1 deletion tutorials/docs/navigation2_on_real_turtlebot3.rst
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,12 @@ Requirements
You must install Nav2, Turtlebot3.
If you don't have them installed, please follow :ref:`getting_started`.

The turtlebot3 software can be installed via the following or on the `turtlebot3 repository <https://github.com/ROBOTIS-GIT/turtlebot3>`_:

.. code-block:: bash
sudo apt install ros-<ros2-distro>-turtlebot3 ros-<ros2-distro>-turtlebot3-msgs ros-<ros2-distro>-turtlebot3-bringup
Tutorial Steps
==============

Expand All @@ -44,7 +50,7 @@ Run the following commands first whenever you open a new terminal during this tu
1- Launch Turtlebot 3
---------------------

You will need to launch your robot's interface,
You will need to launch your robot's interface, for example:

``ros2 launch turtlebot3_bringup robot.launch.py use_sim_time:=False``

Expand Down
1 change: 1 addition & 0 deletions tutorials/docs/navigation2_with_gps.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ It is assumed ROS2 and Nav2 dependent packages are installed or built locally. A
sudo apt install ros-$ROS_DISTRO-tile-map
The code for this tutorial is hosted on `nav2_gps_waypoint_follower_demo <https://github.com/ros-navigation/navigation2_tutorials/tree/master/nav2_gps_waypoint_follower_demo>`_. Though we will go through the most important steps of the setup, it's highly recommended that you clone and build the package when setting up your dev environment.
This is available in ROS 2 Iron and newer.

You may also need to install gazebo and turtlebot3 simulation if you have not executed previous tutorials or Nav2 demos. See Nav2's Getting Started page for more information.

Expand Down
10 changes: 8 additions & 2 deletions tutorials/docs/navigation2_with_slam.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ Overview

This document explains how to use Nav2 with SLAM.
The following steps show ROS 2 users how to generate occupancy grid maps and use Nav2 to move their robot around.
This tutorial applies to both simulated and physical robots, but will be completed here on physical robot.
This tutorial applies to both simulated and physical robots, but will be completed here on a physical robot.

Before completing this tutorial, completing the :ref:`getting_started` is highly recommended especially if you are new to ROS and Navigation2.

Expand Down Expand Up @@ -41,6 +41,12 @@ Tutorial Steps
--------------------------

For this tutorial, we will use the turtlebot3.
The turtlebot3 software can be installed via the following or on the `turtlebot3 repository <https://github.com/ROBOTIS-GIT/turtlebot3>`_:

.. code-block:: bash
sudo apt install ros-<ros2-distro>-turtlebot3 ros-<ros2-distro>-turtlebot3-msgs ros-<ros2-distro>-turtlebot3-bringup
If you have another robot, replace with your robot specific interfaces.
Typically, this includes the robot state publisher of the URDF, simulated or physical robot interfaces, controllers, safety nodes, and the like.

Expand All @@ -50,7 +56,7 @@ Run the following commands first whenever you open a new terminal during this tu
- ``export TURTLEBOT3_MODEL=waffle``


Launch your robot's interface and robot state publisher,
Launch your robot's interface and robot state publisher, for example:

``ros2 launch turtlebot3_bringup robot.launch.py``

Expand Down

0 comments on commit 9fcbec1

Please sign in to comment.