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
이 지침은 공식 설치 가이드를 단순화한 버전입니다. 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
그런 다음, install_geographiclib_datasets.sh
스크립트를 실행하여 GeographicLib 데이터세트를 설치합니다.
sh
wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh
sudo bash ./install_geographiclib_datasets.sh
소스 설치
이 설치는 ~/catkin_ws
에 catkin 작업 공간에서 설치합니다.
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
패키지는 catkin_make를 사용하여 빌드할 수 있지만, 선호하는 방법은 catkin_tools를 사용하는 것입니다. 이는 편리한 빌드 도구이기 때문입니다.
wstool을 처음 사용하는 경우 다음을 사용하여 소스 공간을 초기화합니다.
sh
$ wstool init ~/catkin_ws/src
Now you are ready to do the build:
MAVLink를 설치합니다.
sh# 모든 ROS 배포판에 대해 Kinetic 참조를 사용합니다. 배포판에 국한되지 않고 최신 상태이기 때문입니다. rosinstall_generator --rosdistro kinetic mavlink | tee /tmp/mavros.rosinstall
릴리스 또는 최신 버전을 사용하여 소스에서 MAVROS를 설치합니다.
출시/안정
shrosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
최신 소스
shrosinstall_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
작업 공간과 의존성 만들기
shwstool merge -t src /tmp/mavros.rosinstall wstool update -t src -j4 rosdep install --from-paths src --ignore-src -y
GeographicLib 데이터세트를 설치합니다.
sh./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
소스를 빌드합니다.
shcatkin build
작업 공간에서 setup.bash 또는 setup.zsh를 사용하는지 확인하십시오.
sh#Needed 또는 rosrun이 이 작업 공간에서 노드를 찾을 수 없습니다. source devel/setup.bash
오류가 발생하면, 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.