diff --git a/dev/source/docs/ros2-cartographer-slam.rst b/dev/source/docs/ros2-cartographer-slam.rst index 56ae20225a..d0b5d8db56 100644 --- a/dev/source/docs/ros2-cartographer-slam.rst +++ b/dev/source/docs/ros2-cartographer-slam.rst @@ -4,7 +4,7 @@ Cartographer SLAM with ROS 2 in SITL ==================================== -This page shows how to setup ROS 2 with Ardupilot SITL and run Google Cartographer as a SLAM source. +This page shows how to setup ROS 2 with ArduPilot SITL and run Google Cartographer as a SLAM source. Installation ============ @@ -53,7 +53,7 @@ In another terminal, run: Configure ArduPilot =================== -If you'd like to get the information from Cartographer to go into Ardupilot's extended kalman filter, you will need to change some parameters, you can do that through any GCS, including mavproxy: +If you'd like to get the information from Cartographer to go into ArduPilot's extended kalman filter, you will need to change some parameters, you can do that through any GCS, including mavproxy: - :ref:`AHRS_EKF_TYPE ` = 3 to use EKF3 - :ref:`EK2_ENABLE ` = 0 to disable EKF2 diff --git a/dev/source/docs/ros2-gazebo.rst b/dev/source/docs/ros2-gazebo.rst index c5f5c91aa3..e4f6e96507 100644 --- a/dev/source/docs/ros2-gazebo.rst +++ b/dev/source/docs/ros2-gazebo.rst @@ -4,19 +4,19 @@ ROS 2 with Gazebo ================= -Once ROS2 is correctly :ref:`installed ` and running :ref:`sitl `, we can integrate Ardupilot with Gazebo. +Once ROS2 is correctly :ref:`installed ` and running :ref:`SITL `, we can integrate ArduPilot with Gazebo. -First, `install Gazebo Garden `. +First, `install Gazebo Garden `__. Next, set up all the necessary ROS 2 packages in the workspace. -We will clone the required repositories using `vcstool ` and a `ros2.repos` files: +We will clone the required repositories using `vcstool `__ and a `ros2.repos` files: .. code-block:: bash - cd ~/ros2_ws/src + cd ~/ros2_ws wget https://raw.githubusercontent.com/ArduPilot/ardupilot_gz/main/ros2_gz.repos - vcs import --recursive < ros2_gz.repos + vcs import --recursive src < ros2_gz.repos Set the gazebo version @@ -74,7 +74,7 @@ Examples available ros2 launch ardupilot_gz_bringup iris_maze.launch.py -Here is a demo video of Ardupilot working with ROS 2 and Gazebo: +Here is a demo video of ArduPilot working with ROS 2 and Gazebo: .. youtube:: HZKXrSAE-ac :width: 100% diff --git a/dev/source/docs/ros2-sitl.rst b/dev/source/docs/ros2-sitl.rst index 777e85b7c1..8387fcb43d 100644 --- a/dev/source/docs/ros2-sitl.rst +++ b/dev/source/docs/ros2-sitl.rst @@ -4,7 +4,7 @@ ROS 2 with SITL =============== -Once ROS2 is correctly :ref:`installed `, and SITL is also :ref:`installed `, source your workspace and launch Ardupilot SITL with ROS 2! +Once ROS2 is correctly :ref:`installed `, and SITL is also :ref:`installed `, source your workspace and launch ArduPilot SITL with ROS 2! .. code-block:: bash diff --git a/dev/source/docs/ros2.rst b/dev/source/docs/ros2.rst index 31da5c2292..1c6c636cac 100644 --- a/dev/source/docs/ros2.rst +++ b/dev/source/docs/ros2.rst @@ -9,7 +9,7 @@ ROS 2 ArduPilot capabilities can be extended with `ROS `__ (aka Robot Operating System). -`ROS `__ provides libraries, tools, hardware abstraction, device drivers, visualizers, message-passing, package management, and more to help software developers create robot applications. ROS has been superseded by `ROS2 `__, and Ardupilot now natively supports it through its library `AP_DDS `__. +`ROS `__ provides libraries, tools, hardware abstraction, device drivers, visualizers, message-passing, package management, and more to help software developers create robot applications. ROS has been superseded by `ROS2 `__, and ArduPilot now natively supports it through its library `AP_DDS `__. Prerequisites