리눅스 개발환경
리눅스에서는 모든 PX4 타겟들 (NuttX based hardware, Qualcomm Snapdragon Flight hardware, Linux-based hardware, Simulation, ROS)에 대해서 빌드가 가능합니다.
다음은 지원하는 타겟의 각 개발환경을 수동으로 셋업하는 방법을 설명합니다.
We recommend that you use the Convenience bash scripts to install the Simulators and/or NuttX toolchain (this is easier than typing in the instructions below). Then follow just the additional instructions for other targets (e.g. Qualcomm Snapdragon Flight, Bebop, Raspberry Pi, etc.)
편리한 Bash 스크립트
We've created a number of bash scripts that you can use to install the Simulators and/or NuttX toolchain. All the scripts include the Qt Creator IDE, Ninja Build System, Common Dependencies, FastRTPS, and also download the PX4 source to your computer (~/src/Firmware).
The scripts have been tested on a clean Ubuntu LTS installation. They may not work as expected if installed on top of an existing system.
The scripts are:
- ubuntu_sim.sh: Common Dependencies, jMAVSim simulator, Gazebo8 simulator.
- This contains the common dependencies for all PX4 build targets.
- You can run this before installing the remaining dependencies for Qualcomm Snapdragon Flight or Raspberry Pi/Parrot Bebop.
- ubuntu_sim_nuttx.sh: ubuntu_sim.sh + NuttX tools. This requires computer restart on completion.
- ubuntu_sim_ros_gazebo.sh: ROS/Gazebo and MAVROS.
- ROS is installed with Gazebo7 by default (we have chosen to use the default rather than Gazebo8 to simplify ROS development).
- Your catkin (ROS build system) workspace is created at ~/catkin_ws/.
How to use the scripts
To use the scripts:
- Make the user a member of the group "dialout" (this only has to be done once):
- Open a terminal and enter the following command:
sudo usermod -a -G dialout $USER
- Logout and login again (the change is only made after a new login).
- Open a terminal and enter the following command:
- Download the desired script
- Run the script in a bash shell (e.g. to run ubuntu_sim.sh):
Acknowledge any prompts as the scripts progress.source ubuntu_sim.sh
Permission Setup
Never ever fix permission problems by using
sudo
. It will create more permission problems in the process and require a system re-installation to fix them.
The user needs to be part of the group "dialout":
sudo usermod -a -G dialout $USER
Then logout and login again (the change is only made after a new login).
Remove the modemmanager
Ubuntu comes with a serial modem manager which interferes heavily with any robotics related use of a serial port (or USB serial). It can removed/deinstalled without side effects:
sudo apt-get remove modemmanager
Ninja Build System
Ninja is a faster build system than Make and the PX4 CMake generators support it. To install a recent version, download the binary and add it to your path:
mkdir -p $HOME/ninja
cd $HOME/ninja
wget https://github.com/martine/ninja/releases/download/v1.6.0/ninja-linux.zip
unzip ninja-linux.zip
rm ninja-linux.zip
exportline="export PATH=$HOME/ninja:\$PATH"
if grep -Fxq "$exportline" ~/.profile; then echo nothing to do ; else echo $exportline >> ~/.profile; fi
. ~/.profile
Common Dependencies
Update the package list and install the following dependencies for all PX4 build targets.
sudo add-apt-repository ppa:george-edison55/cmake-3.x -y
sudo apt-get update
sudo apt-get install python-argparse git-core wget zip \
python-empy qtcreator cmake build-essential genromfs -y
# required python packages
sudo apt-get install python-dev -y
sudo apt-get install python-pip
sudo -H pip install pandas jinja2
pip install pyserial
You may also wish to install pyulog. This is is a useful python package that contains scripts to parse ULog files and display them.
# optional python tools
pip install pyulog
FastRTPS installation
eProsima Fast RTPS is a C++ implementation of the RTPS (Real Time Publish Subscribe) protocol. FastRTPS is used, via the RTPS/ROS2 Interface: PX4-FastRTPS Bridge, to allow PX4 uORB topics to be shared with offboard components.
The following instructions can be used to install the FastRTPS 1.5 binaries to your home directory.
wget http://www.eprosima.com/index.php/component/ars/repository/eprosima-fast-rtps/eprosima-fast-rtps-1-5-0/eprosima_fastrtps-1-5-0-linux-tar-gz
mv eprosima_fastrtps-1-5-0-linux-tar-gz eprosima_fastrtps-1-5-0-linux.tar.gz
tar -xzf eprosima_fastrtps-1-5-0-linux.tar.gz eProsima_FastRTPS-1.5.0-Linux/
tar -xzf eprosima_fastrtps-1-5-0-linux.tar.gz requiredcomponents
tar -xzf requiredcomponents/eProsima_FastCDR-1.0.7-Linux.tar.gz
cd eProsima_FastCDR-1.0.7-Linux; ./configure --libdir=/usr/lib; make; sudo make install
cd ..
cd eProsima_FastRTPS-1.5.0-Linux; ./configure --libdir=/usr/lib; make; sudo make install
More "generic" instructions, which additionally cover installation from source, can be found here: Fast RTPS installation.
Simulation Dependencies
The dependencies for the Gazebo and jMAVSim simulators listed below. You should minimally install jMAVSim to make it easy to test the installation. Additional information about these and other supported simulators is covered in: Simulation.
jMAVSim
Install the dependencies for jMAVSim Simulation.
# jMAVSim simulator
sudo apt-get install ant openjdk-8-jdk openjdk-8-jre -y
Gazebo
If you're going work with ROS then follow the ROS/Gazebo instructions in the following section (these install Gazebo automatically, as part of the ROS installation).
Install the dependencies for Gazebo Simulation.
# Gazebo simulator
sudo apt-get install protobuf-compiler libeigen3-dev libopencv-dev -y
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
## Setup keys
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
## Update the debian database:
sudo apt-get update -y
## Install Gazebo8
sudo apt-get install gazebo8 -y
## For developers (who work on top of Gazebo) one extra package
sudo apt-get install libgazebo8-dev
ROS/Gazebo
Install the dependencies for ROS/Gazebo) ("Kinetic"). These include Gazebo7 (at time of writing, the default version that comes with ROS). The instructions come from the ROS Wiki Ubuntu page.
# ROS Kinetic/Gazebo
## Gazebo dependencies
sudo apt-get install protobuf-compiler libeigen3-dev libopencv-dev -y
## ROS Gazebo: http://wiki.ros.org/kinetic/Installation/Ubuntu
## Setup keys
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116
## For keyserver connection problems substitute hkp://pgp.mit.edu:80 or hkp://keyserver.ubuntu.com:80 above.
sudo apt-get update
## Get ROS/Gazebo
sudo apt-get install ros-kinetic-desktop-full -y
## Initialize rosdep
sudo rosdep init
rosdep update
## Setup environment variables
echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
source ~/.bashrc
## Get rosinstall
sudo apt-get install python-rosinstall -y
Install the MAVROS (MAVLink on ROS) package. This enables MAVLink communication between computers running ROS, MAVLink enabled autopilots, and MAVLink enabled GCS.
MAVROS can be installed as a ubuntu package or from source. Source is recommended for developers.
## Create catkin workspace (ROS build system)
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
## Install dependencies
sudo apt-get install python-wstool python-rosinstall-generator python-catkin-tools -y
## Initialise wstool
wstool init ~/catkin_ws/src
## Build MAVROS
### Get source (upstream - released)
rosinstall_generator --upstream mavros | tee /tmp/mavros.rosinstall
### Get latest released mavlink package
rosinstall_generator mavlink | tee -a /tmp/mavros.rosinstall
### Setup workspace & install deps
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src
rosdep install --from-paths src --ignore-src --rosdistro kinetic -y
## Build!
catkin build
## Re-source environment to reflect new packages/build environment
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
NuttX-based Hardware
Install the following dependencies to build for NuttX based hardware: Pixhawk, Pixfalcon, Pixracer, Pixhawk 3, Intel® Aero Ready to Fly Drone.
Packages with specified versions should be installed with the specified package version.
sudo apt-get install python-serial openocd \
flex bison libncurses5-dev autoconf texinfo \
libftdi-dev libtool zlib1g-dev -y
Remove any old versions of the arm-none-eabi toolchain.
sudo apt-get remove gcc-arm-none-eabi gdb-arm-none-eabi binutils-arm-none-eabi gcc-arm-embedded
sudo add-apt-repository --remove ppa:team-gcc-arm-embedded/ppa
Execute the script below to install 5.4:
pushd .
cd ~
wget https://launchpad.net/gcc-arm-embedded/5.0/5-2016-q2-update/+download/gcc-arm-none-eabi-5_4-2016q2-20160622-linux.tar.bz2
tar -jxf gcc-arm-none-eabi-5_4-2016q2-20160622-linux.tar.bz2
exportline="export PATH=$HOME/gcc-arm-none-eabi-5_4-2016q2/bin:\$PATH"
if grep -Fxq "$exportline" ~/.bash_profile; then echo nothing to do ; else echo $exportline >> ~/.profile; fi
popd
Run these commands to install the 32 bit support libraries (this might fail and can be skipped if running a 32 bit OS):
sudo dpkg --add-architecture i386
sudo apt-get update
sudo apt-get install libc6:i386 libgcc1:i386 libstdc++5:i386 libstdc++6:i386
sudo apt-get install gcc-4.6-base:i386
Now restart your machine.
Troubleshooting
Check the version by entering the following command:
arm-none-eabi-gcc --version
The output should be something similar to:
arm-none-eabi-gcc (GNU Tools for ARM Embedded Processors) 5.4.1 20160609 (release) [ARM/embedded-5-branch revision 237715]
Copyright (C) 2015 Free Software Foundation, Inc.
This is free software; see the source for copying conditions. There is NO
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
If you get the following output, make sure you have the 32bit libs installed properly as described in the installation steps:
arm-none-eabi-gcc --version
arm-none-eabi-gcc: No such file or directory
Snapdragon Flight
(Cross) Toolchain installation
sudo apt-get install android-tools-adb android-tools-fastboot \
fakechroot fakeroot unzip xz-utils wget python python-empy -y
Please follow the instructions on https://github.com/ATLFlight/cross_toolchain for the toolchain installation.
Load the new configuration:
source ~/.bashrc
Sysroot Installation
A sysroot is required to provide the libraries and header files needed to cross compile applications for the Snapdragon Flight applications processor.
The qrlSDK sysroot provides the required header files and libraries for the camera, GPU, etc.
Download the file Flight_3.1.3_qrlSDK.tgz and save it in cross_toolchain/download/
.
cd cross_toolchain
unset HEXAGON_ARM_SYSROOT
./qrlinux_sysroot.sh
Append the following to your ~/.bashrc:
export HEXAGON_ARM_SYSROOT=${HOME}/Qualcomm/qrlinux_v3.1.1_sysroot
Load the new configuration:
source ~/.bashrc
For more sysroot options see Sysroot Installation
Update ADSP firmware
Before building, flashing and running code, you'll need to update the ADSP firmware.
References
There is a an external set of documentation for Snapdragon Flight toolchain and SW setup and verification: ATLFlightDocs
Messages from the DSP can be viewed using mini-dm.
${HEXAGON_SDK_ROOT}/tools/debug/mini-dm/Linux_Debug/mini-dm
Note: Alternatively, especially on Mac, you can also use nano-dm.
Raspberry Pi Hardware
Developers working on Raspberry Pi hardware need to download a ARMv7 cross-compiler, either GCC or clang.
The recommended toolchain for raspbian is GCC 4.8.3 and can be cloned from https://github.com/raspberrypi/tools.git
.
The PATH
environmental variable should include the path to the gcc cross-compiler collection of tools (e.g. gcc, g++, strip) prefixed with arm-linux-gnueabihf-
.
git clone https://github.com/raspberrypi/tools.git ${HOME}/rpi-tools
# test compiler
$HOME/rpi-tools/arm-bcm2708/gcc-linaro-arm-linux-gnueabihf-raspbian-x64/bin/arm-linux-gnueabihf-gcc -v
# permanently update PATH variable by modifying ~/.profile
echo 'export PATH=$PATH:$HOME/rpi-tools/arm-bcm2708/gcc-linaro-arm-linux-gnueabihf-raspbian-x64/bin' >> ~/.profile
# update PATH variable only for this session
export PATH=$PATH:$HOME/rpi-tools/arm-bcm2708/gcc-linaro-arm-linux-gnueabihf-raspbian-x64/bin
clang
In order to use clang, you also need GCC.
Download clang for your specific distribution from LLVM Download page and unpack it.
Assuming that you've unpacked clang to CLANG_DIR
, and clang
binary is available in CLANG_DIR/bin
, and you have the GCC cross-compiler in GCC_DIR
, you will need to setup the symlinks for clang in the GCC_DIR
bin dir, and add GCC_DIR/bin
to PATH
.
Example below for building PX4 firmware out of tree, using CMake.
ln -s <CLANG_DIR>/bin/clang <GCC_DIR>/bin/clang
ln -s <CLANG_DIR>/bin/clang++ <GCC_DIR>/bin/clang++
export PATH=<GCC_DIR>/bin:$PATH
cd <PATH-TO-PX4-SRC>
mkdir build/posix_rpi_cross_clang
cd build/posix_rpi_cross_clang
cmake \
-G"Unix Makefiles" \
-DCONFIG=posix_rpi_cross \
-DCMAKE_C_COMPILER=clang \
-DCMAKE_CXX_COMPILER=clang++ \
..
Parrot Bebop
Developers working with the Parrot Bebop should install the RPi Linux Toolchain. Follow the description under Raspberry Pi hardware.
Next, install ADB.
sudo apt-get install android-tools-adb -y
Ground Control Software
Download and install the QGroundControl Daily Build.
Editor / IDE
The development team often use:
- Sublime Text: a fast and lean text editor.
- Qt Creator: A popular open-source IDE.
Next Steps
Once you have finished setting up the environment, continue to the build instructions.