Skip to content

ROS (1) with MAVROS Installation Guide

WARNING

The PX4 development team recommend that all users upgrade to ROS 2. Ця документація відображає "старий підхід".

This documentation explains how to set up communication between the PX4 Autopilot and a ROS 1 enabled companion computer using MAVROS.

MAVROS is a ROS 1 package that enables MAVLink extendable communication between computers running ROS 1 for any MAVLink enabled autopilot, ground station, or peripheral. MAVROS is the "official" supported bridge between ROS 1 and the MAVLink protocol.

First we install PX4 and ROS, and then MAVROS.

Install ROS and PX4

This section explains how to install ROS 1 with PX4. ROS 1 full desktop builds come with Gazebo Classic, so normally you will not install the simulator dependencies yourself!

TIP

These instructions are a simplified version of the official installation guide. They cover the ROS Melodic and Noetic releases.

Install MAVROS

Then MAVROS can be installed either from source or binary. Ми рекомендуємо розробникам використовувати початкове встановлення.

Бінарне встановлення (Debian / Ubuntu)

The ROS repository has binary packages for Ubuntu x86, amd64 (x86_64) and armhf (ARMv7). Kinetic також підтримує Debian Jessie amd64 і arm64 (ARMv8).

Use apt-get for installation, where ${ROS_DISTRO} below should resolve to kinetic or noetic, depending on your version of ROS:

sh
sudo apt-get install ros-${ROS_DISTRO}-mavros ros-${ROS_DISTRO}-mavros-extras ros-${ROS_DISTRO}-mavros-msgs

Then install GeographicLib datasets by running the install_geographiclib_datasets.sh script:

sh
wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh
sudo bash ./install_geographiclib_datasets.sh

Встановлення початкового коду

This installation assumes you have a catkin workspace located at ~/catkin_ws If you don't create one with:

sh
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
wstool init src

You will be using the ROS Python tools: wstool (for retrieving sources), rosinstall, and catkin_tools (building) for this installation. Хоча вони могли бути встановлені під час інсталяції ROS, ви також можете встановити їх разом з ним:

sh
sudo apt-get install python-catkin-tools python-rosinstall-generator -y

TIP

While the package can be built using catkin_make the preferred method is using catkin_tools as it is a more versatile and "friendly" build tool.

Якщо це ваш перший раз за допомогою wstool вам потрібно буде ініціалізувати свій вихідний простір з:

sh
$ wstool init ~/catkin_ws/src

Тепер ви готові зробити збірку:

  1. Встановіть MAVLink:

    sh
    # We use the Kinetic reference for all ROS distros as it's not distro-specific and up to date
    rosinstall_generator --rosdistro kinetic mavlink | tee /tmp/mavros.rosinstall
  2. Встановити MAVROS з джерела, використовуючи як випущену, так і останню версію:

    • Випущений реліз/стабільний

      sh
      rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
    • Найновіше джерело

      sh
      rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall
      sh
      # For fetching all the dependencies into your catkin_ws,
      # just add '--deps' to the above scripts, E.g.:
      #   rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall
  3. Create workspace & deps

    sh
    wstool merge -t src /tmp/mavros.rosinstall
    wstool update -t src -j4
    rosdep install --from-paths src --ignore-src -y
  4. Install GeographicLib datasets:

    sh
    ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
  5. Джерело збірки

    sh
    catkin build
  6. Переконайтеся, що ви використовуєте setup.bash або setup.zsh з робочого простору.

    sh
    #Needed or rosrun can't find nodes from this workspace.
    source devel/setup.bash

In the case of error, there are addition installation and troubleshooting notes in the mavros repo.

MAVROS Приклади

The MAVROS Offboard Example (C++), will show you the basics of MAVROS, from reading telemetry, checking the drone state, changing flight modes and controlling the drone.

INFO

If you have an example app using the PX4 Autopilot and MAVROS, we can help you get it on our docs.

Дивіться також