mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 03:07:34 +08:00
Merged master into stable
This commit is contained in:
@@ -64,7 +64,6 @@ CMakeLists.txt.user
|
||||
GPATH
|
||||
GRTAGS
|
||||
GTAGS
|
||||
*.config
|
||||
*.creator
|
||||
*.creator.user
|
||||
*.files
|
||||
|
||||
+6
-3
@@ -1,12 +1,15 @@
|
||||
[submodule "mavlink/include/mavlink/v1.0"]
|
||||
path = mavlink/include/mavlink/v1.0
|
||||
url = git://github.com/mavlink/c_library.git
|
||||
url = https://github.com/mavlink/c_library_v1.git
|
||||
[submodule "mavlink/include/mavlink/v2.0"]
|
||||
path = mavlink/include/mavlink/v2.0
|
||||
url = https://github.com/mavlink/c_library_v2.git
|
||||
[submodule "NuttX"]
|
||||
path = NuttX
|
||||
url = git://github.com/PX4/NuttX.git
|
||||
url = https://github.com/PX4/NuttX.git
|
||||
[submodule "src/modules/uavcan/libuavcan"]
|
||||
path = src/modules/uavcan/libuavcan
|
||||
url = git://github.com/UAVCAN/libuavcan.git
|
||||
url = https://github.com/UAVCAN/libuavcan.git
|
||||
[submodule "Tools/genmsg"]
|
||||
path = Tools/genmsg
|
||||
url = https://github.com/ros/genmsg.git
|
||||
|
||||
+80
-92
@@ -7,129 +7,117 @@ matrix:
|
||||
fast_finish: true
|
||||
include:
|
||||
- os: linux
|
||||
sudo: false
|
||||
env: GCC_VER=4.8
|
||||
- os: linux
|
||||
sudo: false
|
||||
env: GCC_VER=4.9
|
||||
sudo: required
|
||||
env: GCC_VER=4.8 DOCKER_REPO="px4io/px4-dev-base:2016-07-14"
|
||||
services:
|
||||
- docker
|
||||
- os: osx
|
||||
osx_image: xcode7
|
||||
sudo: true
|
||||
osx_image: xcode7.3
|
||||
env: CCACHE_CPP2=1
|
||||
|
||||
cache:
|
||||
ccache: true
|
||||
pip: true
|
||||
directories:
|
||||
- $HOME/.ccache
|
||||
|
||||
addons:
|
||||
apt:
|
||||
sources:
|
||||
- kubuntu-backports
|
||||
- ubuntu-toolchain-r-test
|
||||
- george-edison55-precise-backports
|
||||
packages:
|
||||
- build-essential
|
||||
- ccache
|
||||
- clang-3.5
|
||||
- cmake
|
||||
- g++-4.9
|
||||
- gcc-4.9
|
||||
- genromfs
|
||||
- libc6-i386
|
||||
- libncurses5-dev
|
||||
- ninja-build
|
||||
- python-argparse
|
||||
- python-empy
|
||||
- s3cmd
|
||||
- texinfo
|
||||
- zlib1g-dev
|
||||
- $HOME/.pip/cache/
|
||||
- $HOME/Library/Caches/pip
|
||||
|
||||
before_install:
|
||||
- if [ "${TRAVIS_OS_NAME}" = "linux" ]; then
|
||||
pushd .
|
||||
&& cd ~ && mkdir gcc && cd gcc
|
||||
&& if [ "$GCC_VER" = "4.8" ]; then GCC_URL="https://launchpadlibrarian.net/186124160/gcc-arm-none-eabi-4_8-2014q3-20140805-linux.tar.bz2" ; fi
|
||||
&& if [ "$GCC_VER" = "4.9" ]; then GCC_URL="https://launchpad.net/gcc-arm-embedded/4.9/4.9-2014-q4-major/+download/gcc-arm-none-eabi-4_9-2014q4-20141203-linux.tar.bz2" ; fi
|
||||
&& wget -O gcc.tar.bz2 ${GCC_URL}
|
||||
&& tar -jxf gcc.tar.bz2 --strip 1
|
||||
&& exportline="export PATH=$HOME/gcc/bin:\$PATH"
|
||||
&& if grep -Fxq "$exportline" ~/.profile; then echo nothing to do ; else echo $exportline >> ~/.profile; fi
|
||||
&& . ~/.profile
|
||||
&& popd
|
||||
&& git clone git://github.com/PX4/CI-Tools.git
|
||||
&& ./CI-Tools/s3cmd-configure
|
||||
&& mkdir -p ~/bin
|
||||
&& wget -O ~/bin/astyle https://github.com/PX4/astyle/releases/download/2.05.1/astyle-linux && chmod +x ~/bin/astyle
|
||||
&& astyle --version
|
||||
&& if [ "$CXX" = "g++" ]; then export CXX="g++-4.9" CC="gcc-4.9"; fi
|
||||
cd ${TRAVIS_BUILD_DIR}
|
||||
&& git fetch --unshallow && git fetch --all --tags
|
||||
&& docker pull ${DOCKER_REPO}
|
||||
;
|
||||
elif [ "${TRAVIS_OS_NAME}" = "osx" ]; then
|
||||
brew tap PX4/homebrew-px4
|
||||
&& brew update; brew update
|
||||
&& brew install cmake ninja
|
||||
&& brew install genromfs
|
||||
&& sudo easy_install pip
|
||||
&& sudo pip install empy
|
||||
sudo -H easy_install pip
|
||||
&& sudo -H pip install empy
|
||||
&& wget https://s3.amazonaws.com/px4-travis/toolchain/macos/ccache
|
||||
&& sudo mv ccache /usr/local/bin
|
||||
&& chmod +x /usr/local/bin/ccache
|
||||
&& mkdir -p ~/bin
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/c++
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/cc
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/clang
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/clang++
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/g++
|
||||
&& sudo ln -s /usr/local/bin/ccache ~/bin/gcc
|
||||
&& export PATH=~/bin:$PATH
|
||||
&& wget https://s3.amazonaws.com/px4-travis/toolchain/macos/ninja
|
||||
&& sudo mv ninja /usr/local/bin
|
||||
&& chmod +x /usr/local/bin/ninja
|
||||
;
|
||||
fi
|
||||
|
||||
before_script:
|
||||
# setup ccache
|
||||
- mkdir -p ~/bin
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-g++
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-gcc
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-size
|
||||
- ln -s /usr/bin/ccache ~/bin/arm-none-eabi-objcopy
|
||||
- ln -s /usr/bin/ccache ~/bin/clang++
|
||||
- ln -s /usr/bin/ccache ~/bin/clang++-3.4
|
||||
- ln -s /usr/bin/ccache ~/bin/clang++-3.5
|
||||
- ln -s /usr/bin/ccache ~/bin/clang
|
||||
- ln -s /usr/bin/ccache ~/bin/clang-3.4
|
||||
- ln -s /usr/bin/ccache ~/bin/clang-3.5
|
||||
- export PATH=~/bin:$PATH
|
||||
|
||||
env:
|
||||
global:
|
||||
- NINJA_BUILD=1
|
||||
# AWS KEY: $PX4_AWS_KEY
|
||||
- secure: "XknnZHWBbpHbN4f3fuAVwUztdLIu8ej4keC3aQSDofo3uw8AFEzojfsQsN9u77ShWSIV4iYJWh9C9ALkCx7TocJ+xYjiboo10YhM9lH/8u+EXjYWG6GHS8ua0wkir+cViSxoLNaMtmcb/rPTicJecAGANxLsIHyBAgTL3fkbLSA="
|
||||
# AWS SECRET: $PX4_AWS_SECRET
|
||||
- secure: "h6oajlW68dWIr+wZhO58Dv6e68dZHrBLVA6lPXZmheFQBW6Xam1HuLGA0LOW6cL9TnrAsOZ8g4goB58eMQnMEijFZKi3mhRwZhd/Xjq/ZGJOWBUrLoQHZUw2dQk5ja5vmUlKEoQnFZjDuMjx8KfX5ZMNy8A3yssWZtJYHD8c+bk="
|
||||
- PX4_AWS_BUCKET=px4-travis
|
||||
- GIT_SUBMODULES_ARE_EVIL=1
|
||||
|
||||
script:
|
||||
- git submodule update --quiet --init --recursive
|
||||
- ccache -M 1GB; ccache -z
|
||||
- if [ "${TRAVIS_OS_NAME}" = "linux" ]; then
|
||||
arm-none-eabi-gcc --version && make check VECTORCONTROL=1;
|
||||
docker run --rm -v `pwd`:`pwd`:rw -v $HOME/.ccache:$HOME/.ccache:rw -e CCACHE_DIR=$HOME/.ccache -e GIT_SUBMODULES_ARE_EVIL=1 -w=`pwd` --user=$UID -it ${DOCKER_REPO} /bin/bash -c "make check_qgc_firmware VECTORCONTROL=1";
|
||||
elif [ "${TRAVIS_OS_NAME}" = "osx" ]; then
|
||||
make check_posix_sitl_default;
|
||||
fi
|
||||
- ccache -s
|
||||
|
||||
after_success:
|
||||
- if [[ "${TRAVIS_OS_NAME}" = "linux" && "${GCC_VER}" = "4.8" ]]; then
|
||||
make package_firmware
|
||||
&& find . -name \*.px4 -exec cp "{}" . \;
|
||||
&& find . -maxdepth 1 -mindepth 1 -type f -name 'nuttx-*-default.px4' | sed 's/.\/nuttx-//' | sed 's/-default.px4//' | xargs -I{} mv nuttx-{}-default.px4 {}_default.px4
|
||||
&& ./CI-Tools/s3cmd-put `find . -maxdepth 1 -mindepth 1 -type f -name '*_default.px4'` build_px4fmu-v2_default/parameters.xml build_px4fmu-v2_default/airframes.xml CI-Tools/directory/index.html Firmware/$TRAVIS_BRANCH/
|
||||
&& ./CI-Tools/s3cmd-put Firmware.zip archives/Firmware/$TRAVIS_BRANCH/$TRAVIS_BUILD_ID/
|
||||
&& ./CI-Tools/s3cmd-put CI-Tools/directory/index.html archives/Firmware/$TRAVIS_BRANCH/
|
||||
&& ./CI-Tools/s3cmd-put CI-Tools/index.html index.html
|
||||
&& ./CI-Tools/s3cmd-put CI-Tools/timestamp.html timestamp.html
|
||||
&& echo ""
|
||||
&& echo "Binaries have been posted to:" https://px4-travis.s3.amazonaws.com/archives/Firmware/$TRAVIS_BRANCH/$TRAVIS_BUILD_ID/Firmware.zip
|
||||
;
|
||||
- make package_firmware && mkdir s3deploy-archive && cp Firmware.zip s3deploy-archive/
|
||||
# find all px4 firmware (*.px4) and rename
|
||||
- find . -type f -name 'nuttx-*-default.px4' -exec cp "{}" . \;
|
||||
- find . -maxdepth 1 -mindepth 1 -type f -name 'nuttx-*-default.px4' | sed 's/.\/nuttx-//' | sed 's/-default.px4//' | xargs -I{} mv nuttx-{}-default.px4 {}_default.px4
|
||||
- mkdir s3deploy-branch && mv *_default.px4 build_px4fmu-v2_default/parameters.xml build_px4fmu-v2_default/airframes.xml s3deploy-branch/
|
||||
# only deploy GCC 4.8 builds on master/beta/stable
|
||||
- if [[ "$GCC_VER" == "4.8" && ( "$TRAVIS_BRANCH" == "master" || "$TRAVIS_BRANCH" == "beta" || "$TRAVIS_BRANCH" == "stable" ) ]]; then
|
||||
export PX4_S3_DEPLOY=1;
|
||||
fi
|
||||
|
||||
deploy:
|
||||
provider: releases
|
||||
api_key:
|
||||
secure: cdHWLRBxA5UlYpOS0Sp891QK7PFmMgQ5ZWs1aPt+sw0rIrowyWMHCwXNBEdUqaExHYNYgXCUDI0EzNgfB7ZcR63Qv1MQeoyamV4jsxlyAqDqmxNtWO82S6RhHGeMLk26VgFKzynVcEk1IYlQP2nqzMQLdu+jTrngERuAIrCdRuc=
|
||||
file: "Firmware.zip"
|
||||
skip_cleanup: true
|
||||
on:
|
||||
tags: true
|
||||
all_branches: true
|
||||
repo: PX4/Firmware
|
||||
condition: $GCC_VER = 4.8
|
||||
# deploy *.px4 to S3 px4-travis/Firmware/$TRAVIS_BRANCH
|
||||
- provider: s3
|
||||
access_key_id: $PX4_AWS_KEY
|
||||
secret_access_key:
|
||||
secure: $PX4_AWS_SECRET
|
||||
bucket: px4-travis
|
||||
local_dir: s3deploy-branch
|
||||
upload-dir: Firmware/$TRAVIS_BRANCH
|
||||
acl: public_read
|
||||
skip_cleanup: true
|
||||
on:
|
||||
all_branches: true
|
||||
condition: $PX4_S3_DEPLOY = 1
|
||||
|
||||
# deploy Firmware.zip to S3 px4-travis/archives/Firmware/$TRAVIS_BRANCH/$TRAVIS_BUILD_ID
|
||||
- provider: s3
|
||||
access_key_id: $PX4_AWS_KEY
|
||||
secret_access_key:
|
||||
secure: $PX4_AWS_SECRET
|
||||
bucket: px4-travis
|
||||
local_dir: s3deploy-archive
|
||||
upload-dir: archives/Firmware/$TRAVIS_BRANCH/$TRAVIS_BUILD_ID
|
||||
acl: public_read
|
||||
skip_cleanup: true
|
||||
on:
|
||||
all_branches: true
|
||||
condition: $PX4_S3_DEPLOY = 1
|
||||
|
||||
# on tags deploy Firmware.zip to Github releases
|
||||
- provider: releases
|
||||
api_key:
|
||||
secure: cdHWLRBxA5UlYpOS0Sp891QK7PFmMgQ5ZWs1aPt+sw0rIrowyWMHCwXNBEdUqaExHYNYgXCUDI0EzNgfB7ZcR63Qv1MQeoyamV4jsxlyAqDqmxNtWO82S6RhHGeMLk26VgFKzynVcEk1IYlQP2nqzMQLdu+jTrngERuAIrCdRuc=
|
||||
file: "Firmware.zip"
|
||||
skip_cleanup: true
|
||||
on:
|
||||
tags: true
|
||||
all_branches: true
|
||||
repo: PX4/Firmware
|
||||
condition: $GCC_VER = 4.8
|
||||
|
||||
notifications:
|
||||
webhooks:
|
||||
|
||||
+38
-7
@@ -132,7 +132,7 @@ cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
|
||||
set(CMAKE_BUILD_TYPE "" CACHE STRING "build type")
|
||||
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY
|
||||
STRINGS ";Debug;Release;RelWithDebInfo;MinSizeRel")
|
||||
set(CONFIG "nuttx_px4fmu-v2_default" CACHE STRING "desired configuration")
|
||||
set(CONFIG "posix_sitl_default" CACHE STRING "desired configuration")
|
||||
file(GLOB_RECURSE configs RELATIVE cmake/configs "cmake/configs/*.cmake")
|
||||
set_property(CACHE CONFIG PROPERTY STRINGS ${configs})
|
||||
set(THREADS "4" CACHE STRING
|
||||
@@ -152,6 +152,17 @@ set(target_name "${OS}-${BOARD}-${LABEL}")
|
||||
|
||||
message(STATUS "${target_name}")
|
||||
|
||||
# Define GNU standard installation directories
|
||||
include(GNUInstallDirs)
|
||||
|
||||
# Setup install paths
|
||||
if(NOT CMAKE_INSTALL_PREFIX)
|
||||
if (${OS} STREQUAL "posix")
|
||||
set(CMAKE_INSTALL_PREFIX "/usr" CACHE PATH "Install path prefix" FORCE)
|
||||
endif()
|
||||
endif()
|
||||
message(STATUS "CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}")
|
||||
|
||||
# switch to ros CMake file if building ros
|
||||
if (${OS} STREQUAL "ros")
|
||||
include("cmake/ros-CMakeLists.txt")
|
||||
@@ -202,7 +213,7 @@ if (NOT ${CMAKE_VERSION} VERSION_LESS 3.1.0)
|
||||
endif()
|
||||
|
||||
set(version_major 1)
|
||||
set(version_minor 0)
|
||||
set(version_minor 4)
|
||||
set(version_patch 1)
|
||||
set(version "${version_major}.${version_minor}.${version_patch}")
|
||||
set(package-contact "px4users@googlegroups.com")
|
||||
@@ -235,7 +246,7 @@ endforeach()
|
||||
px4_add_git_submodule(TARGET git_genmsg PATH "Tools/genmsg")
|
||||
px4_add_git_submodule(TARGET git_gencpp PATH "Tools/gencpp")
|
||||
px4_add_git_submodule(TARGET git_mavlink PATH "mavlink/include/mavlink/v1.0")
|
||||
px4_add_git_submodule(TARGET git_gtest PATH "unittets/gtest")
|
||||
px4_add_git_submodule(TARGET git_gtest PATH "unittests/gtest")
|
||||
px4_add_git_submodule(TARGET git_uavcan PATH "src/modules/uavcan/libuavcan")
|
||||
px4_add_git_submodule(TARGET git_nuttx PATH "NuttX")
|
||||
px4_add_git_submodule(TARGET git_driverframework PATH "src/lib/DriverFramework")
|
||||
@@ -295,11 +306,11 @@ add_definitions(${definitions})
|
||||
#=============================================================================
|
||||
# source code generation
|
||||
#
|
||||
file(GLOB_RECURSE msg_files msg/*.msg)
|
||||
add_subdirectory(msg)
|
||||
px4_generate_messages(TARGET msg_gen
|
||||
MSG_FILES ${msg_files}
|
||||
OS ${OS}
|
||||
DEPENDS git_genmsg git_gencpp
|
||||
DEPENDS git_genmsg git_gencpp prebuild_targets
|
||||
)
|
||||
px4_generate_parameters_xml(OUT parameters.xml BOARD ${BOARD})
|
||||
px4_generate_airframes_xml(OUT airframes.xml BOARD ${BOARD})
|
||||
@@ -348,6 +359,9 @@ foreach(module ${config_module_list})
|
||||
#message(STATUS "adding module: ${module}")
|
||||
endforeach()
|
||||
|
||||
# Keep track of external shared libs required for modules
|
||||
set(module_external_libraries "${module_external_libraries}" CACHE INTERNAL "module_external_libraries")
|
||||
|
||||
add_subdirectory(src/firmware/${OS})
|
||||
|
||||
#add_dependencies(df_driver_framework nuttx_export_${CONFIG}.stamp)
|
||||
@@ -368,10 +382,27 @@ px4_create_git_hash_header(HEADER ${CMAKE_BINARY_DIR}/build_git_version.h)
|
||||
#
|
||||
# Important to having packaging at end of cmake file.
|
||||
#
|
||||
set(CPACK_PACKAGE_NAME ${PROJECT_NAME}-${CONFIG})
|
||||
set(CPACK_PACKAGE_VERSION ${version})
|
||||
set(CPACK_PACKAGE_CONTACT ${package_contact})
|
||||
set(CPACK_PACKAGE_CONTACT ${package-contact})
|
||||
set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON)
|
||||
set(CPACK_DEBIAN_PACKAGE_SECTION "devel")
|
||||
set(CPACK_DEBIAN_PACKAGE_PRIORITY "optional")
|
||||
set(short-description "The px4 autopilot.")
|
||||
set(CPACK_DEBIAN_PACKAGE_DESCRIPTION ${short-description})
|
||||
set(CPACK_GENERATOR "ZIP")
|
||||
set(CPACK_SOURCE_GENERATOR "ZIP")
|
||||
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${CONFIG}-${version}")
|
||||
set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${version}")
|
||||
set(CPACK_SOURCE_GENERATOR "ZIP;TBZ2")
|
||||
if ("${CMAKE_SYSTEM}" MATCHES "Linux")
|
||||
find_program(DPKG_PROGRAM dpkg)
|
||||
if (EXISTS ${DPKG_PROGRAM})
|
||||
list (APPEND CPACK_GENERATOR "DEB")
|
||||
endif()
|
||||
endif()
|
||||
if (${OS} STREQUAL "posix")
|
||||
set(CPACK_SET_DESTDIR "ON")
|
||||
endif()
|
||||
include(CPack)
|
||||
|
||||
endif() # ros alternative endif
|
||||
|
||||
@@ -66,8 +66,8 @@ Linux or Eagle with a working IP interface (?? does this need further instructio
|
||||
> adb shell
|
||||
# bash
|
||||
root@linaro-developer:/# cd ???
|
||||
root@linaro-developer:/# ./mainapp
|
||||
App name: mainapp
|
||||
root@linaro-developer:/# ./px4
|
||||
App name: px4
|
||||
Enter a command and its args:
|
||||
uorb start
|
||||
muorb start
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
{
|
||||
"board_id": 9,
|
||||
"magic": "PX4FWv2",
|
||||
"description": "Firmware for the MindPx-V2 board",
|
||||
"board_id": 88,
|
||||
"magic": "MindPX",
|
||||
"description": "Firmware for the MindPXFMUv2 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "MindPx-v2",
|
||||
"summary": "MindPXFMUv2",
|
||||
"version": "2.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
|
||||
@@ -0,0 +1,12 @@
|
||||
{
|
||||
"board_id": 78,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the TAPv1 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "TAPv1",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -50,11 +50,11 @@ ifneq ($(CMAKE_VER),0)
|
||||
$(warning sudo apt-get install cmake)
|
||||
$(warning )
|
||||
$(warning Official website:)
|
||||
$(warning wget https://cmake.org/files/v3.3/cmake-3.3.2-Linux-x86_64.sh)
|
||||
$(warning chmod +x cmake-3.3.2-Linux-x86_64.sh)
|
||||
$(warning sudo mkdir /opt/cmake-3.3.2)
|
||||
$(warning sudo ./cmake-3.3.2-Linux-x86_64.sh --prefix=/opt/cmake-3.3.2 --exclude-subdir)
|
||||
$(warning export PATH=/opt/cmake-3.3.2/bin:$$PATH)
|
||||
$(warning wget https://cmake.org/files/v3.4/cmake-3.4.3-Linux-x86_64.sh)
|
||||
$(warning chmod +x cmake-3.4.3-Linux-x86_64.sh)
|
||||
$(warning sudo mkdir /opt/cmake-3.4.3)
|
||||
$(warning sudo ./cmake-3.4.3-Linux-x86_64.sh --prefix=/opt/cmake-3.4.3 --exclude-subdir)
|
||||
$(warning export PATH=/opt/cmake-3.4.3/bin:$$PATH)
|
||||
$(warning )
|
||||
$(error Fatal)
|
||||
endif
|
||||
@@ -77,7 +77,7 @@ endif
|
||||
# in that directory with the target upload.
|
||||
|
||||
# explicity set default build target
|
||||
all: px4fmu-v2_default
|
||||
all: posix_sitl_default
|
||||
|
||||
# Parsing
|
||||
# --------------------------------------------------------------------
|
||||
@@ -104,14 +104,27 @@ endif
|
||||
PX4_MAKE_ARGS = -j$(j) --no-print-directory
|
||||
endif
|
||||
|
||||
# check if replay env variable is set & set build dir accordingly
|
||||
ifdef replay
|
||||
BUILD_DIR_SUFFIX := _replay
|
||||
else
|
||||
BUILD_DIR_SUFFIX :=
|
||||
endif
|
||||
|
||||
# Functions
|
||||
# --------------------------------------------------------------------
|
||||
# describe how to build a cmake config
|
||||
define cmake-build
|
||||
+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(PWD)/build_$@/Makefile ]; then rm -rf $(PWD)/build_$@; fi
|
||||
+@if [ ! -e $(PWD)/build_$@/CMakeCache.txt ]; then Tools/check_submodules.sh && mkdir -p $(PWD)/build_$@ && cd $(PWD)/build_$@ && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1) || (cd .. && rm -rf $(PWD)/build_$@); fi
|
||||
+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e ./build_$@$(BUILD_DIR_SUFFIX)/Makefile ]; then rm -rf ./build_$@$(BUILD_DIR_SUFFIX); fi
|
||||
+@if [ ! -e ./build_$@$(BUILD_DIR_SUFFIX)/CMakeCache.txt ]; then Tools/check_submodules.sh && mkdir -p ./build_$@$(BUILD_DIR_SUFFIX) && cd ./build_$@$(BUILD_DIR_SUFFIX) && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1) || (cd .. && rm -rf ./build_$@$(BUILD_DIR_SUFFIX)); fi
|
||||
+@Tools/check_submodules.sh
|
||||
+@(echo "PX4 CONFIG: $@" && cd $(PWD)/build_$@ && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
|
||||
+@(echo "PX4 CONFIG: $@$(BUILD_DIR_SUFFIX)" && cd ./build_$@$(BUILD_DIR_SUFFIX) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
|
||||
endef
|
||||
|
||||
define cmake-build-other
|
||||
+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e ./build_$@/Makefile ]; then rm -rf ./build_$@; fi
|
||||
+@if [ ! -e ./build_$@/CMakeCache.txt ]; then Tools/check_submodules.sh && mkdir -p ./build_$@ && cd ./build_$@ && cmake $(2) -G$(PX4_CMAKE_GENERATOR) || (cd .. && rm -rf ./build_$@); fi
|
||||
+@(cd ./build_$@ && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
|
||||
endef
|
||||
|
||||
# create empty targets to avoid msgs for targets passed to cmake
|
||||
@@ -131,12 +144,18 @@ endef
|
||||
# --------------------------------------------------------------------
|
||||
# Do not put any spaces between function arguments.
|
||||
|
||||
tap-v1_default:
|
||||
$(call cmake-build,nuttx_tap-v1_default)
|
||||
|
||||
px4fmu-v1_default:
|
||||
$(call cmake-build,nuttx_px4fmu-v1_default)
|
||||
|
||||
px4fmu-v2_default:
|
||||
$(call cmake-build,nuttx_px4fmu-v2_default)
|
||||
|
||||
px4fmu-v2_test:
|
||||
$(call cmake-build,nuttx_px4fmu-v2_test)
|
||||
|
||||
px4fmu-v4_default:
|
||||
$(call cmake-build,nuttx_px4fmu-v4_default)
|
||||
|
||||
@@ -155,9 +174,6 @@ posix_sitl_default:
|
||||
posix_sitl_lpe:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_sitl_ekf2:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_sitl_replay:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
@@ -177,12 +193,13 @@ posix_eagle_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
eagle_default: posix_eagle_default qurt_eagle_default
|
||||
eagle_legacy_default: posix_eagle_legacy_driver_default qurt_eagle_legacy_driver_default
|
||||
|
||||
qurt_eagle_legacy_driver_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_eagle_legacy_driver_default:
|
||||
$(call cmake-build,$@)
|
||||
$(call cmake-build,$@)
|
||||
|
||||
qurt_excelsior_default:
|
||||
$(call cmake-build,$@)
|
||||
@@ -192,10 +209,13 @@ posix_excelsior_default:
|
||||
|
||||
excelsior_default: posix_excelsior_default qurt_excelsior_default
|
||||
|
||||
posix_rpi2_default:
|
||||
posix_rpi_native:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_rpi2_release:
|
||||
posix_rpi_cross:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_bebop_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix: posix_sitl_default
|
||||
@@ -213,8 +233,14 @@ run_sitl_ros: sitl_deprecation
|
||||
# Other targets
|
||||
# --------------------------------------------------------------------
|
||||
|
||||
.PHONY: uavcan_firmware check check_format unittest tests package_firmware clean submodulesclean distclean
|
||||
.NOTPARALLEL: uavcan_firmware check check_format unittest tests package_firmware clean submodulesclean distclean
|
||||
.PHONY: gazebo_build uavcan_firmware check check_format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
|
||||
.NOTPARALLEL: gazebo_build uavcan_firmware check check_format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
|
||||
|
||||
gazebo_build:
|
||||
@mkdir -p build_gazebo
|
||||
@if [ ! -e ./build_gazebo/CMakeCache.txt ];then cd build_gazebo && cmake -Wno-dev -G$(PX4_CMAKE_GENERATOR) ../Tools/sitl_gazebo; fi
|
||||
@cd build_gazebo && $(PX4_MAKE) $(PX4_MAKE_ARGS)
|
||||
@cd build_gazebo && $(PX4_MAKE) $(PX4_MAKE_ARGS) sdf
|
||||
|
||||
uavcan_firmware:
|
||||
ifeq ($(VECTORCONTROL),1)
|
||||
@@ -222,12 +248,39 @@ ifeq ($(VECTORCONTROL),1)
|
||||
@(rm -rf vectorcontrol && git clone --quiet --depth 1 https://github.com/thiemar/vectorcontrol.git && cd vectorcontrol && BOARD=s2740vc_1_0 make --silent --no-print-directory && BOARD=px4esc_1_6 make --silent --no-print-directory && ../Tools/uavcan_copy.sh)
|
||||
endif
|
||||
|
||||
check: check_px4fmu-v1_default check_px4fmu-v2_default check_px4fmu-v4_default_and_uavcan check_mindpx-v2_default check_px4-stm32f4discovery_default check_posix_sitl_default check_unittest check_format
|
||||
checks_defaults: \
|
||||
check_px4fmu-v1_default \
|
||||
check_px4fmu-v2_default \
|
||||
check_mindpx-v2_default \
|
||||
check_px4-stm32f4discovery_default \
|
||||
check_tap-v1_default \
|
||||
|
||||
checks_bootloaders: \
|
||||
|
||||
|
||||
checks_tests: \
|
||||
check_px4fmu-v2_test
|
||||
|
||||
checks_alts: \
|
||||
check_px4fmu-v2_ekf2 \
|
||||
|
||||
checks_uavcan: \
|
||||
check_px4fmu-v4_default_and_uavcan
|
||||
|
||||
checks_sitls: \
|
||||
check_posix_sitl_default
|
||||
|
||||
checks_last: \
|
||||
check_tests \
|
||||
check_format \
|
||||
|
||||
check: checks_defaults checks_tests checks_alts checks_uavcan checks_bootloaders checks_last
|
||||
quick_check: check_px4fmu-v2_default check_px4fmu-v4_default check_tests check_format
|
||||
|
||||
check_format:
|
||||
$(call colorecho,"Checking formatting with astyle")
|
||||
@./Tools/fix_code_style.sh
|
||||
@./Tools/check_code_style.sh
|
||||
@./Tools/check_code_style_all.sh
|
||||
|
||||
check_%:
|
||||
@echo
|
||||
@@ -245,7 +298,30 @@ ifeq ($(VECTORCONTROL),1)
|
||||
endif
|
||||
|
||||
unittest: posix_sitl_default
|
||||
@(cd unittests && cmake -G$(PX4_CMAKE_GENERATOR) && $(PX4_MAKE) $(PX4_MAKE_ARGS) && ctest -j2 --output-on-failure)
|
||||
$(call cmake-build-other,unittest, ../unittests)
|
||||
@(cd build_unittest && ctest -j2 --output-on-failure)
|
||||
|
||||
run_tests_posix: posix_sitl_default
|
||||
@mkdir -p build_posix_sitl_default/src/firmware/posix/rootfs/fs/microsd
|
||||
@mkdir -p build_posix_sitl_default/src/firmware/posix/rootfs/eeprom
|
||||
@touch build_posix_sitl_default/src/firmware/posix/rootfs/eeprom/parameters
|
||||
@(cd build_posix_sitl_default/src/firmware/posix && ./px4 -d ../../../../posix-configs/SITL/init/rcS_tests | tee test_output)
|
||||
@(cd build_posix_sitl_default/src/firmware/posix && grep --color=always "All tests passed" test_output)
|
||||
|
||||
tests: check_unittest run_tests_posix
|
||||
|
||||
# QGroundControl flashable firmware
|
||||
qgc_firmware: \
|
||||
check_px4fmu-v1_default \
|
||||
check_px4fmu-v2_default \
|
||||
check_mindpx-v2_default \
|
||||
check_px4fmu-v4_default_and_uavcan \
|
||||
check_format
|
||||
|
||||
extra_firmware: \
|
||||
check_px4-stm32f4discovery_default \
|
||||
check_px4fmu-v2_test \
|
||||
check_px4fmu-v2_ekf2
|
||||
|
||||
package_firmware:
|
||||
@zip --junk-paths Firmware.zip `find . -name \*.px4`
|
||||
@@ -255,18 +331,18 @@ clean:
|
||||
@(cd NuttX/nuttx && make clean)
|
||||
|
||||
submodulesclean:
|
||||
@git submodule sync
|
||||
@git submodule sync --recursive
|
||||
@git submodule deinit -f .
|
||||
@git submodule update --init --recursive --force
|
||||
|
||||
distclean: submodulesclean
|
||||
@git clean -ff -x -d
|
||||
@git clean -ff -x -d -e ".project" -e ".cproject"
|
||||
|
||||
# targets handled by cmake
|
||||
cmake_targets = test upload package package_source debug debug_tui debug_ddd debug_io debug_io_tui debug_io_ddd check_weak \
|
||||
cmake_targets = install test upload package package_source debug debug_tui debug_ddd debug_io debug_io_tui debug_io_ddd check_weak \
|
||||
run_cmake_config config gazebo gazebo_gdb gazebo_lldb jmavsim replay \
|
||||
jmavsim_gdb jmavsim_lldb gazebo_gdb_iris gazebo_lldb_tailsitter gazebo_iris gazebo_iris_opt_flow gazebo_tailsitter \
|
||||
gazebo_gdb_standard_vtol gazebo_lldb_standard_vtol gazebo_standard_vtol gazebo_plane
|
||||
gazebo_gdb_standard_vtol gazebo_lldb_standard_vtol gazebo_standard_vtol gazebo_plane gazebo_solo gazebo_typhoon_h480
|
||||
$(foreach targ,$(cmake_targets),$(eval $(call cmake-targ,$(targ))))
|
||||
|
||||
.PHONY: clean
|
||||
|
||||
+1
-1
Submodule NuttX updated: f0f4bdc872...55e8d557ec
@@ -1,6 +1,6 @@
|
||||
## PX4 Pro Drone Autopilot ##
|
||||
|
||||
[](https://travis-ci.org/PX4/Firmware) [](https://scan.coverity.com/projects/3966?tab=overview)
|
||||
[](https://github.com/PX4/Firmware/releases) [](https://zenodo.org/badge/latestdoi/22634/PX4/Firmware) [](https://travis-ci.org/PX4/Firmware) [](https://scan.coverity.com/projects/3966?tab=overview)
|
||||
|
||||
[](https://gitter.im/PX4/Firmware?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
|
||||
|
||||
|
||||
@@ -25,8 +25,8 @@ then
|
||||
param set MC_YAWRATE_I 0.25
|
||||
param set MC_YAWRATE_D 0.0
|
||||
|
||||
param set BAT_V_SCALING 0.00989
|
||||
param set BAT_C_SCALING 0.0124
|
||||
param set BAT_V_DIV 12.27559
|
||||
param set BAT_A_PER_V 15.39103
|
||||
fi
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
# @maintainer Lorenz Meier <lorenz@px4.io>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
@@ -21,10 +21,3 @@ then
|
||||
param set MC_PITCHRATE_D 0.004
|
||||
param set MC_YAW_P 4
|
||||
fi
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
set PWM_MIN 1100
|
||||
set PWM_MAX 1950
|
||||
|
||||
@@ -15,22 +15,28 @@ then
|
||||
param set VT_MOT_COUNT 4
|
||||
param set VT_TRANS_THR 0.75
|
||||
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLL_P 6.5
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
param set MC_ROLLRATE_I 0.002
|
||||
param set MC_ROLLRATE_I 0.01
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_ROLLRATE_FF 0.0
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.12
|
||||
param set MC_PITCHRATE_I 0.002
|
||||
param set MC_PITCH_P 6.5
|
||||
param set MC_PITCHRATE_P 0.15
|
||||
param set MC_PITCHRATE_I 0.01
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_PITCHRATE_FF 0.0
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAW_P 3.5
|
||||
param set MC_YAW_FF 0.5
|
||||
param set MC_YAWRATE_P 0.22
|
||||
param set MC_YAWRATE_I 0.02
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAWRATE_FF 0.0
|
||||
param set MC_YAWRATE_MAX 20
|
||||
param set MC_YAWRAUTO_MAX 20
|
||||
|
||||
param set MPC_XY_P 0.8
|
||||
param set MPC_XY_VEL_P 0.1
|
||||
param set MPC_ACC_HOR_MAX 2.0
|
||||
|
||||
param set VT_MOT_COUNT 4
|
||||
param set VT_IDLE_PWM_MC 1080
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name CruiseAder Claire
|
||||
#
|
||||
# @type VTOL Tiltrotor
|
||||
#
|
||||
# @maintainer Samay Siga <samay_s@icloud.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.vtol_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set VT_TYPE 1
|
||||
param set VT_TILT_MC 0.08
|
||||
param set VT_TILT_TRANS 0.5
|
||||
param set VT_TILT_FW 0.9
|
||||
|
||||
param set VT_MOT_COUNT 4
|
||||
param set VT_IDLE_PWM_MC 1080
|
||||
param set VT_TYPE 1
|
||||
fi
|
||||
|
||||
set MIXER claire
|
||||
set PWM_OUT 1234
|
||||
set PWM_RATE 400
|
||||
set PWM_MAX 2000
|
||||
|
||||
set MIXER_AUX claire
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_RATE 123
|
||||
set PWM_AUX_MIN 1000
|
||||
set PWM_AUX_MAX 2000
|
||||
set PWM_AUX_DISARMED 1000
|
||||
|
||||
set MAV_TYPE 21
|
||||
@@ -1,6 +1,6 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name Coaxial Helicopter (such as Esky Lama v4 or Esky Big Lama)
|
||||
# @name Esky (Big) Lama v4
|
||||
#
|
||||
# @type Coaxial Helicopter
|
||||
#
|
||||
@@ -12,7 +12,8 @@
|
||||
# @maintainer Emmanuel Roussel
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
set MIXER coax
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
@@ -47,7 +48,6 @@ then
|
||||
param set MC_YAWRATE_FF 0
|
||||
fi
|
||||
|
||||
set MIXER coax
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_OUT 34
|
||||
set PWM_RATE 400
|
||||
@@ -62,4 +62,3 @@ set PWM_AUX_OUT 1234
|
||||
set PWM_AUX_DISARMED 1500
|
||||
set PWM_AUX_MIN 1000
|
||||
set PWM_AUX_MAX 2000
|
||||
|
||||
|
||||
@@ -11,31 +11,44 @@ sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 20
|
||||
param set FW_AIRSPD_MIN 12
|
||||
param set FW_AIRSPD_TRIM 16
|
||||
param set FW_R_TC 0.3
|
||||
param set FW_P_TC 0.3
|
||||
param set FW_L1_DAMPING 0.74
|
||||
param set FW_L1_PERIOD 16
|
||||
param set FW_AIRSPD_MAX 25
|
||||
param set FW_AIRSPD_MIN 12.5
|
||||
param set FW_AIRSPD_TRIM 16.5
|
||||
param set LNDFW_AIRSPD_MAX 6
|
||||
param set LNDFW_VELI_MAX 4
|
||||
param set LNDFW_VEL_XY_MAX 3
|
||||
param set LNDFW_VEL_Z_MAX 5
|
||||
param set FW_R_TC 0.4
|
||||
param set FW_P_TC 0.4
|
||||
param set FW_THR_CRUISE 0.55
|
||||
param set FW_L1_DAMPING 0.75
|
||||
param set FW_L1_PERIOD 15
|
||||
param set FW_LND_ANG 15
|
||||
param set FW_LND_FLALT 5
|
||||
param set FW_LND_FLALT 8
|
||||
param set FW_LND_HHDIST 15
|
||||
param set FW_LND_HVIRT 13
|
||||
param set FW_LND_TLALT 5
|
||||
param set FW_LND_TLALT 10
|
||||
param set FW_THR_LND_MAX 0
|
||||
param set FW_PR_FF 0.35
|
||||
param set FW_P_LIM_MAX 20
|
||||
param set FW_P_LIM_MIN -30
|
||||
param set FW_R_LIM 45
|
||||
param set FW_PR_FF 0.45
|
||||
param set FW_PR_IMAX 0.4
|
||||
param set FW_PR_P 0.08
|
||||
param set FW_RR_FF 0.6
|
||||
param set FW_PR_P 0.005
|
||||
param set FW_RR_FF 0.45
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.04
|
||||
param set FW_RR_P 0.013
|
||||
param set FW_P_RMAX_NEG 70
|
||||
param set FW_P_RMAX_POS 70
|
||||
param set FW_R_RMAX 70
|
||||
param set SYS_COMPANION 157600
|
||||
param set PWM_MAIN_REV0 1
|
||||
param set PWM_MAIN_REV1 1
|
||||
param set PWM_MAIN_REV2 1
|
||||
param set PWM_DISARMED 0
|
||||
param set PWM_MIN 900
|
||||
param set PWM_MAX 2100
|
||||
param set MIS_TAKEOFF_ALT 50
|
||||
param set NAV_LOITER_RAD 30
|
||||
fi
|
||||
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
|
||||
@@ -0,0 +1,34 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name Lumenier QAV-R (raceblade) 5" arms
|
||||
#
|
||||
# @type Quadrotor x
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer James Goppert <james.goppert@gmail.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 8.0
|
||||
param set MC_ROLLRATE_P 0.08
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 8.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.05
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.15
|
||||
param set MC_YAWRATE_I 0.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.5
|
||||
param set PWM_MIN 1075
|
||||
param set MPC_THR_MIN 0.06
|
||||
param set MPC_MANTHR_MIN 0.06
|
||||
fi
|
||||
@@ -29,7 +29,7 @@ then
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.8
|
||||
|
||||
param set BAT_V_SCALING 0.00838095238
|
||||
param set BAT_V_DIV 34.32838
|
||||
fi
|
||||
|
||||
set OUTPUT_MODE ardrone
|
||||
|
||||
@@ -79,7 +79,7 @@ then
|
||||
param set RC5_TRIM 1500
|
||||
fi
|
||||
|
||||
set MIXER solo
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
set MIXER_AUX none
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
ekf_att_pos_estimator start
|
||||
ekf2 start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
|
||||
@@ -11,7 +11,12 @@ then
|
||||
param set RTL_DESCEND_ALT 100
|
||||
param set RTL_LAND_DELAY -1
|
||||
|
||||
param set NAV_ACC_RAD 50
|
||||
# FW uses L1 distance for acceptance radius
|
||||
# set a smaller NAV_ACC_RAD for vertical acceptance distance
|
||||
param set NAV_ACC_RAD 10
|
||||
|
||||
param set MIS_LTRMIN_ALT 25
|
||||
param set MIS_TAKEOFF_ALT 25
|
||||
|
||||
param set PE_VELNE_NOISE 0.3
|
||||
param set PE_VELD_NOISE 0.35
|
||||
|
||||
@@ -45,10 +45,10 @@ then
|
||||
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
echo "[i] Mixer: $MIXER_FILE on $OUTPUT_DEV"
|
||||
echo "INFO [init] Mixer: $MIXER_FILE on $OUTPUT_DEV"
|
||||
else
|
||||
echo "[i] Error loading mixer: $MIXER_FILE"
|
||||
echo "ERROR: Could not load mixer: $MIXER_FILE" >> $LOG_FILE
|
||||
echo "ERROR [init] Error loading mixer: $MIXER_FILE"
|
||||
echo "ERROR:[init] Could not load mixer: $MIXER_FILE" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
@@ -56,8 +56,8 @@ then
|
||||
else
|
||||
if [ $MIXER != skip ]
|
||||
then
|
||||
echo "[i] Mixer not defined"
|
||||
echo "ERROR: Mixer not defined" >> $LOG_FILE
|
||||
echo "ERROR [init] Mixer not defined"
|
||||
echo "ERROR [init] Mixer not defined" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -137,10 +137,10 @@ then
|
||||
then
|
||||
if mixer load $OUTPUT_AUX_DEV $MIXER_AUX_FILE
|
||||
then
|
||||
echo "[i] Mixer: $MIXER_AUX_FILE on $OUTPUT_AUX_DEV"
|
||||
echo "INFO [init] Mixer: $MIXER_AUX_FILE on $OUTPUT_AUX_DEV"
|
||||
else
|
||||
echo "[i] Error loading mixer: $MIXER_AUX_FILE"
|
||||
echo "ERROR: Could not load mixer: $MIXER_AUX_FILE" >> $LOG_FILE
|
||||
echo "ERROR [init] Error loading mixer: $MIXER_AUX_FILE"
|
||||
echo "ERROR [init] Could not load mixer: $MIXER_AUX_FILE" >> $LOG_FILE
|
||||
fi
|
||||
else
|
||||
set PWM_AUX_OUT none
|
||||
|
||||
@@ -29,19 +29,9 @@ then
|
||||
fi
|
||||
#---------------------------------------
|
||||
|
||||
if mc_att_control start
|
||||
then
|
||||
else
|
||||
# try the multiplatform version
|
||||
mc_att_control_m start
|
||||
fi
|
||||
mc_att_control start
|
||||
|
||||
if mc_pos_control start
|
||||
then
|
||||
else
|
||||
# try the multiplatform version
|
||||
mc_pos_control_m start
|
||||
fi
|
||||
mc_pos_control start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
|
||||
@@ -14,6 +14,17 @@ else
|
||||
fmu i2c 1 100000
|
||||
fmu i2c 2 100000
|
||||
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
# We know there are sketchy boards out there
|
||||
# as chinese companies produce Pixracers without
|
||||
# fully understanding the critical parts of the
|
||||
# schematic and BOM, leading to sensor brownouts
|
||||
# on boot. Original Pixracers following the
|
||||
# open hardware design do not require this.
|
||||
fmu sensor_reset 20
|
||||
fi
|
||||
|
||||
if ms5611 -s start
|
||||
then
|
||||
fi
|
||||
@@ -190,7 +201,7 @@ else
|
||||
fi
|
||||
fi
|
||||
|
||||
if sf10a start
|
||||
if sf1xx start
|
||||
then
|
||||
fi
|
||||
|
||||
|
||||
@@ -1,29 +0,0 @@
|
||||
#!nsh
|
||||
#
|
||||
# UAVCAN initialization script.
|
||||
#
|
||||
|
||||
#
|
||||
# Starting stuff according to UAVCAN_ENABLE value
|
||||
#
|
||||
if param greater UAVCAN_ENABLE 0
|
||||
then
|
||||
if uavcan start
|
||||
then
|
||||
echo "[i] UAVCAN started"
|
||||
else
|
||||
echo "[i] ERROR: Could not start UAVCAN"
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
if param greater UAVCAN_ENABLE 1
|
||||
then
|
||||
if uavcan start fw
|
||||
then
|
||||
echo "[i] UAVCAN servers started"
|
||||
else
|
||||
echo "[i] ERROR: Could not start UAVCAN servers"
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -1,9 +0,0 @@
|
||||
#!nsh
|
||||
#
|
||||
# USB MAVLink start
|
||||
#
|
||||
|
||||
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
exit
|
||||
@@ -32,9 +32,9 @@ else
|
||||
then
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[i] microSD card formatted"
|
||||
echo "INFO [init] MicroSD card formatted"
|
||||
else
|
||||
echo "[i] format failed"
|
||||
echo "ERROR [init] Format failed"
|
||||
tone_alarm MNBG
|
||||
set LOG_FILE /dev/null
|
||||
fi
|
||||
@@ -50,7 +50,7 @@ fi
|
||||
set FRC /fs/microsd/etc/rc.txt
|
||||
if [ -f $FRC ]
|
||||
then
|
||||
echo "[i] Executing script: $FRC"
|
||||
echo "INFO [init] Executing script: $FRC"
|
||||
sh $FRC
|
||||
set MODE custom
|
||||
fi
|
||||
@@ -109,6 +109,16 @@ then
|
||||
set AUTOCNF yes
|
||||
else
|
||||
set AUTOCNF no
|
||||
|
||||
#
|
||||
# Release 1.4.0 transitional support:
|
||||
# set to old default if unconfigured.
|
||||
# this preserves the previous behaviour
|
||||
#
|
||||
if param compare BAT_N_CELLS 0
|
||||
then
|
||||
param set BAT_N_CELLS 3
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
@@ -173,7 +183,7 @@ then
|
||||
#
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
echo "[i] No autostart"
|
||||
echo "INFO [init] No autostart"
|
||||
else
|
||||
sh /etc/init.d/rc.autostart
|
||||
fi
|
||||
@@ -192,7 +202,7 @@ then
|
||||
set FCONFIG /fs/microsd/etc/config.txt
|
||||
if [ -f $FCONFIG ]
|
||||
then
|
||||
echo "[i] Custom: $FCONFIG"
|
||||
echo "INFO [init] Custom: $FCONFIG"
|
||||
sh $FCONFIG
|
||||
fi
|
||||
unset FCONFIG
|
||||
@@ -223,7 +233,7 @@ then
|
||||
|
||||
if px4io checkcrc ${IO_FILE}
|
||||
then
|
||||
echo "PX4IO CRC OK" >> $LOG_FILE
|
||||
echo "INFO [init] PX4IO CRC OK" >> $LOG_FILE
|
||||
|
||||
set IO_PRESENT yes
|
||||
else
|
||||
@@ -246,16 +256,16 @@ then
|
||||
usleep 500000
|
||||
if px4io checkcrc $IO_FILE
|
||||
then
|
||||
echo "PX4IO CRC OK after updating" >> $LOG_FILE
|
||||
echo "INFO [init] PX4IO CRC OK after updating" >> $LOG_FILE
|
||||
tone_alarm MLL8CDE
|
||||
|
||||
set IO_PRESENT yes
|
||||
else
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
echo "ERROR [init] PX4IO update failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed" >> $LOG_FILE
|
||||
echo "ERROR [init] PX4IO update failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -263,7 +273,7 @@ then
|
||||
|
||||
if [ $IO_PRESENT == no ]
|
||||
then
|
||||
echo "ERROR: PX4IO not found" >> $LOG_FILE
|
||||
echo "ERROR [init] PX4IO not found" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -330,6 +340,11 @@ then
|
||||
commander start
|
||||
fi
|
||||
|
||||
#
|
||||
# Start CPU load monitor
|
||||
#
|
||||
load_mon start
|
||||
|
||||
#
|
||||
# Start primary output
|
||||
#
|
||||
@@ -350,7 +365,7 @@ then
|
||||
then
|
||||
if param compare UAVCAN_ENABLE 0
|
||||
then
|
||||
echo "[i] OVERRIDING UAVCAN_ENABLE = 1"
|
||||
echo "INFO [init] OVERRIDING UAVCAN_ENABLE = 1" >> $LOG_FILE
|
||||
param set UAVCAN_ENABLE 1
|
||||
fi
|
||||
fi
|
||||
@@ -361,7 +376,7 @@ then
|
||||
then
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "PX4IO start failed" >> $LOG_FILE
|
||||
echo "INFO [init] PX4IO start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -371,7 +386,7 @@ then
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
else
|
||||
echo "FMU start failed" >> $LOG_FILE
|
||||
echo "ERR [init] FMU start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
@@ -403,7 +418,7 @@ then
|
||||
if mkblctrl $MKBLCTRL_ARG
|
||||
then
|
||||
else
|
||||
echo "ERROR: MK start failed" >> $LOG_FILE
|
||||
echo "ERROR [init] MK start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
unset MKBLCTRL_ARG
|
||||
@@ -415,7 +430,7 @@ then
|
||||
if pwm_out_sim mode_port2_pwm8
|
||||
then
|
||||
else
|
||||
echo "PWM SIM start failed" >> $LOG_FILE
|
||||
echo "ERROR [init] PWM SIM start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -431,7 +446,7 @@ then
|
||||
then
|
||||
sh /etc/init.d/rc.io
|
||||
else
|
||||
echo "PX4IO start failed" >> $LOG_FILE
|
||||
echo "ERROR [init] PX4IO start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -441,7 +456,7 @@ then
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
else
|
||||
echo "FMU mode_$FMU_MODE start failed" >> $LOG_FILE
|
||||
echo "ERROR [init] FMU mode_$FMU_MODE start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
@@ -525,25 +540,17 @@ then
|
||||
# clear pins 5 and 6
|
||||
if param compare SENS_EN_LL40LS 1
|
||||
then
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
fi
|
||||
if param greater TRIG_MODE 0
|
||||
then
|
||||
# Get FMU driver out of the way
|
||||
set MIXER_AUX none
|
||||
set AUX_MODE none
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
camera_trigger start
|
||||
fi
|
||||
fi
|
||||
|
||||
# Transitional support: Disable safety on all Pixracer boards
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
if param set CBRK_IO_SAFETY 22027
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Starting stuff according to UAVCAN_ENABLE value
|
||||
#
|
||||
@@ -586,6 +593,12 @@ then
|
||||
sf0x start
|
||||
fi
|
||||
|
||||
# mb12xx sonar sensor
|
||||
if param compare SENS_EN_MB12XX 1
|
||||
then
|
||||
mb12xx start
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
frsky_telemetry start -d /dev/ttyS6
|
||||
@@ -612,26 +625,36 @@ then
|
||||
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
if [ -d /fs/microsd ]
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if ver hwcmp PX4FMU_V1
|
||||
if sdlog2 start -r 30 -a -b 2 -t
|
||||
then
|
||||
if sdlog2 start -r 30 -a -b 2 -t
|
||||
fi
|
||||
else
|
||||
# check if we should increase logging rate for ekf2 replay message logging
|
||||
if param greater EKF2_REC_RPL 0
|
||||
then
|
||||
if param compare SYS_LOGGER 0
|
||||
then
|
||||
fi
|
||||
else
|
||||
# check if we should increase logging rate for ekf2 replay message logging
|
||||
if param greater EKF2_REC_RPL 0
|
||||
then
|
||||
if sdlog2 start -r 500 -e -b 20 -t
|
||||
if sdlog2 start -r 500 -e -b 18 -t
|
||||
then
|
||||
fi
|
||||
else
|
||||
if sdlog2 start -r 100 -a -b 12 -t
|
||||
if logger start -r 500
|
||||
then
|
||||
fi
|
||||
fi
|
||||
else
|
||||
if param compare SYS_LOGGER 0
|
||||
then
|
||||
if sdlog2 start -r 100 -a -b 9 -t
|
||||
then
|
||||
fi
|
||||
else
|
||||
if logger start -b 12 -t
|
||||
then
|
||||
fi
|
||||
fi
|
||||
@@ -651,7 +674,7 @@ then
|
||||
#
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
then
|
||||
echo "FIXED WING"
|
||||
echo "INFO [init] Fixedwing"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
@@ -679,11 +702,11 @@ then
|
||||
#
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
then
|
||||
echo "MULTICOPTER"
|
||||
echo "INFO [init] Multicopter"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
echo "Mixer undefined"
|
||||
echo "INFO [init] Mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
@@ -721,12 +744,16 @@ then
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
if [ $MIXER == coax ]
|
||||
then
|
||||
set MAV_TYPE 3
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
echo "Unknown MAV_TYPE"
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 2
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
@@ -744,11 +771,11 @@ then
|
||||
#
|
||||
if [ $VEHICLE_TYPE == vtol ]
|
||||
then
|
||||
echo "VTOL"
|
||||
echo "INFO [init] VTOL"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
echo "VTOL mixer undefined"
|
||||
echo "WARN [init] VTOL mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
@@ -771,7 +798,7 @@ then
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
echo "Unknown MAV_TYPE"
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 19
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
@@ -855,14 +882,14 @@ then
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "[i] No autostart ID found"
|
||||
echo "WARN [init] No autostart ID found"
|
||||
fi
|
||||
|
||||
# Start any custom addons
|
||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||
if [ -f $FEXTRAS ]
|
||||
then
|
||||
echo "[i] Addons script: $FEXTRAS"
|
||||
echo "INFO [init] Addons script: $FEXTRAS"
|
||||
sh $FEXTRAS
|
||||
fi
|
||||
unset FEXTRAS
|
||||
@@ -886,7 +913,7 @@ mavlink boot_complete
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
echo "NSH EXIT"
|
||||
echo "INFO [init] NSH exit"
|
||||
exit
|
||||
fi
|
||||
unset EXIT_ON_END
|
||||
|
||||
Binary file not shown.
@@ -0,0 +1,38 @@
|
||||
# mixer for the CruiseAder Claire tilt mechansim servo, aileron and elevator
|
||||
|
||||
=======================================================================
|
||||
|
||||
|
||||
Tilt mechanism servo mixer
|
||||
|
||||
---------------------------
|
||||
|
||||
M: 1
|
||||
|
||||
O: 10000 10000 0 -10000 10000
|
||||
|
||||
S: 1 4 10000 10000 0 -10000 10000
|
||||
|
||||
|
||||
|
||||
Aileron mixers
|
||||
|
||||
-------------
|
||||
|
||||
M: 1
|
||||
|
||||
O: 10000 10000 0 -10000 10000
|
||||
|
||||
S: 1 0 10000 10000 0 -10000 10000
|
||||
|
||||
|
||||
|
||||
Elevator mixers
|
||||
|
||||
-------------
|
||||
|
||||
M: 1
|
||||
|
||||
O: 10000 10000 0 -10000 10000
|
||||
|
||||
S: 1 1 -10000 -10000 0 -10000 10000
|
||||
@@ -0,0 +1,7 @@
|
||||
# CruiseAder Claire Main Multirotor mixer for PX4FMU
|
||||
|
||||
#
|
||||
|
||||
#===========================
|
||||
|
||||
R: 4x 10000 10000 10000 0
|
||||
@@ -1,26 +0,0 @@
|
||||
Mixer for SITL plane, using the VTOL airframe for now
|
||||
=========================================================
|
||||
|
||||
Z:
|
||||
|
||||
Z:
|
||||
|
||||
Z:
|
||||
|
||||
Z:
|
||||
|
||||
# mixer for the elevons
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 5000 5000 0 -10000 10000
|
||||
S: 0 1 -5000 -5000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 5000 5000 0 -10000 10000
|
||||
S: 0 1 5000 5000 0 -10000 10000
|
||||
|
||||
# mixer for the pusher/puller throttle
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
@@ -1,18 +0,0 @@
|
||||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a quadrotor in the V configuration. All controls
|
||||
are mixed 100%.
|
||||
|
||||
R: 4v 10000 10000 10000 0
|
||||
|
||||
Gimbal / payload mixer for last two channels
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 3 5 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 3 6 10000 10000 0 -10000 10000
|
||||
@@ -6,13 +6,21 @@ are mixed 100%.
|
||||
|
||||
R: 4x 10000 10000 10000 0
|
||||
|
||||
#mixer for the elevons
|
||||
Z:
|
||||
|
||||
# left elevon
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 5000 5000 0 -10000 10000
|
||||
S: 1 1 5000 5000 0 -10000 10000
|
||||
|
||||
# right elevon
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 5000 5000 0 -10000 10000
|
||||
S: 1 1 -5000 -5000 0 -10000 10000
|
||||
|
||||
# mixer for the virtual elevator
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 1 10000 10000 0 -10000 10000
|
||||
|
||||
@@ -1,7 +0,0 @@
|
||||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a quadrotor in the X configuration. All controls
|
||||
are mixed 100%.
|
||||
|
||||
R: 4x 10000 10000 10000 0
|
||||
@@ -19,13 +19,13 @@ input is inverted between the two servos.
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 -6000 -6000 0 -10000 10000
|
||||
S: 1 1 6500 6500 0 -10000 10000
|
||||
S: 1 0 -8000 -8000 0 -10000 10000
|
||||
S: 1 1 8000 8000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 -6000 -6000 0 -10000 10000
|
||||
S: 1 1 -6500 -6500 0 -10000 10000
|
||||
S: 1 0 -8000 -8000 0 -10000 10000
|
||||
S: 1 1 -8000 -8000 0 -10000 10000
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
|
||||
@@ -0,0 +1,201 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard startup script for PX4FMU v1, v2, v3, v4 onboard sensor drivers.
|
||||
#
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
if ms5611 start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# Configure all I2C buses to 100 KHz as they
|
||||
# are all external or slow
|
||||
fmu i2c 1 100000
|
||||
fmu i2c 2 100000
|
||||
|
||||
if ms5611 -s start
|
||||
then
|
||||
fi
|
||||
|
||||
# Blacksheep telemetry
|
||||
if bst start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if adc start
|
||||
then
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V2
|
||||
then
|
||||
# External I2C bus
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
fi
|
||||
|
||||
# External I2C bus
|
||||
if lis3mdl -X start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal I2C bus
|
||||
if hmc5883 -C -T -I -R 4 start
|
||||
then
|
||||
fi
|
||||
|
||||
# external MPU6K is rotated 180 degrees yaw
|
||||
if mpu6000 -X -R 4 start
|
||||
then
|
||||
set BOARD_FMUV3 true
|
||||
else
|
||||
set BOARD_FMUV3 false
|
||||
fi
|
||||
|
||||
if [ $BOARD_FMUV3 == true ]
|
||||
then
|
||||
# external L3GD20H is rotated 180 degrees yaw
|
||||
if l3gd20 -X -R 4 start
|
||||
then
|
||||
fi
|
||||
|
||||
# external LSM303D is rotated 270 degrees yaw
|
||||
if lsm303d -X -R 6 start
|
||||
then
|
||||
fi
|
||||
|
||||
# internal MPU6000 is rotated 180 deg roll, 270 deg yaw
|
||||
if mpu6000 -R 14 start
|
||||
then
|
||||
fi
|
||||
|
||||
if hmc5883 -C -T -S -R 8 start
|
||||
then
|
||||
fi
|
||||
|
||||
if meas_airspeed start -b 2
|
||||
then
|
||||
fi
|
||||
|
||||
else
|
||||
# FMUv2
|
||||
if mpu6000 start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
# External I2C bus
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if lis3mdl -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus is rotated 90 deg yaw
|
||||
if hmc5883 -C -T -S -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
|
||||
if mpu6000 -R 2 -T 20608 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus mpu9250 is rotated 90 deg yaw
|
||||
if mpu9250 -R 2 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V1
|
||||
then
|
||||
# FMUv1
|
||||
if mpu6000 start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
fi
|
||||
|
||||
# MAG selection
|
||||
if param compare SENS_EXT_MAG 2
|
||||
then
|
||||
if hmc5883 -C -I start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# Use only external as primary
|
||||
if param compare SENS_EXT_MAG 1
|
||||
then
|
||||
if hmc5883 -C -X start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# auto-detect the primary, prefer external
|
||||
if hmc5883 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp MINDPX_V2
|
||||
then
|
||||
if mpu6500 start
|
||||
then
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
fi
|
||||
|
||||
# External I2C bus
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if lis3mdl -R 2 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if meas_airspeed start
|
||||
then
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if sf1xx start
|
||||
then
|
||||
fi
|
||||
|
||||
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
|
||||
usleep 20000
|
||||
if sensors start
|
||||
then
|
||||
fi
|
||||
+10
-112
@@ -38,6 +38,11 @@ fi
|
||||
# Start a minimal system
|
||||
#
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Load parameters
|
||||
#
|
||||
@@ -104,131 +109,24 @@ then
|
||||
tests mount
|
||||
fi
|
||||
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
ver all
|
||||
|
||||
#
|
||||
# Run unit tests at board boot, reporting failure as needed.
|
||||
# Add new unit tests using the same pattern as below.
|
||||
#
|
||||
|
||||
if mavlink_tests
|
||||
then
|
||||
else
|
||||
set unit_test_failure 1
|
||||
set unit_test_failure_list "${unit_test_failure_list} mavlink_tests"
|
||||
fi
|
||||
|
||||
if commander_tests
|
||||
then
|
||||
else
|
||||
set unit_test_failure 1
|
||||
set unit_test_failure_list "${unit_test_failure_list} commander_tests"
|
||||
fi
|
||||
|
||||
if uorb test
|
||||
then
|
||||
else
|
||||
set unit_test_failure 1
|
||||
set unit_test_failure_list "${unit_test_failure_list} uorb_tests"
|
||||
fi
|
||||
|
||||
# Start all sensors on all boards
|
||||
ms5611 start
|
||||
adc start
|
||||
|
||||
if mpu6000 -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if mpu6000 start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
fi
|
||||
|
||||
# MAG selection
|
||||
if param compare SENS_EXT_MAG 2
|
||||
then
|
||||
if hmc5883 -I start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# Use only external as primary
|
||||
if param compare SENS_EXT_MAG 1
|
||||
then
|
||||
if hmc5883 -X start
|
||||
then
|
||||
fi
|
||||
else
|
||||
# auto-detect the primary, prefer external
|
||||
if hmc5883 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V2
|
||||
then
|
||||
if lsm303d -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
fi
|
||||
|
||||
if ms5611 -X start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if meas_airspeed start
|
||||
then
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if sensors start
|
||||
then
|
||||
fi
|
||||
|
||||
# Check for flow sensor
|
||||
if px4flow start
|
||||
then
|
||||
fi
|
||||
|
||||
if ll40ls start
|
||||
then
|
||||
fi
|
||||
|
||||
if tests all
|
||||
then
|
||||
else
|
||||
set unit_test_failure 1
|
||||
set unit_test_failure_list "${unit_test_failure_list} system_tests"
|
||||
fi
|
||||
|
||||
if [ $unit_test_failure == 0 ]
|
||||
then
|
||||
echo
|
||||
echo "All Unit Tests PASSED"
|
||||
rgbled rgb 20 255 20
|
||||
else
|
||||
echo
|
||||
echo "Some Unit Tests FAILED:${unit_test_failure_list}"
|
||||
echo "Some Unit Tests FAILED"
|
||||
rgbled rgb 255 20 20
|
||||
fi
|
||||
|
||||
ver all
|
||||
|
||||
free
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
Mixer for SITL plane
|
||||
=========================================================
|
||||
|
||||
Z:
|
||||
|
||||
Z:
|
||||
|
||||
# mixer for the rudder
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 2 10000 10000 0 -10000 10000
|
||||
|
||||
# mixer for the flaps
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 4 10000 10000 0 -10000 10000
|
||||
|
||||
# mixer for the pusher/puller throttle
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
# mixer for the left aileron
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -10000 -10000 0 -10000 10000
|
||||
|
||||
# mixer for the right aileron
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
|
||||
# mixer for the elevator
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 1 10000 10000 0 -10000 10000
|
||||
+16
-14
@@ -1,24 +1,26 @@
|
||||
Mixer for standard vtol plane (SITL) with motor x configuration
|
||||
=========================================================
|
||||
|
||||
This file defines a single mixer for a standard vtol plane (SITL gazebo) with motors in X configuration.
|
||||
The plane has two ailerons and one elevator. The ailerons and elevator are treated as elevons
|
||||
in order to make the standard vtol simulation compatible with the tailsitter simulation.
|
||||
This file defines a single mixer for a standard vtol plane (SITL gazebo) with motors in X configuration. The plane has two ailerons and one elevator.
|
||||
|
||||
R: 4x 10000 10000 10000 0
|
||||
|
||||
# mixer for the elevons
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 5000 5000 0 -10000 10000
|
||||
S: 1 1 -5000 -5000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 5000 5000 0 -10000 10000
|
||||
S: 1 1 5000 5000 0 -10000 10000
|
||||
|
||||
# mixer for the pusher/puller throttle
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 3 0 20000 -10000 -10000 10000
|
||||
|
||||
# mixer for the left aileron
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 10000 10000 0 -10000 10000
|
||||
|
||||
# mixer for the right aileron
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 0 -10000 -10000 0 -10000 10000
|
||||
|
||||
# mixer for the elevator
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 1 1 10000 10000 0 -10000 10000
|
||||
@@ -0,0 +1,18 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name Generic Quadrotor X config
|
||||
#
|
||||
# @type Quadrotor x
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer Lorenz Meier <lorenz@px4.io>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
@@ -0,0 +1,19 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name Generic Hexarotor x geometry
|
||||
#
|
||||
# @type Hexarotor x
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer Anton Babushkin <anton@px4.io>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER hexa_x
|
||||
|
||||
# Need to set all 8 channels
|
||||
set PWM_OUT 12345678
|
||||
@@ -0,0 +1,20 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for fixed wing
|
||||
#
|
||||
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
ekf2 start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
#
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
#
|
||||
land_detector start fixedwing
|
||||
@@ -0,0 +1,28 @@
|
||||
#!nsh
|
||||
|
||||
set VEHICLE_TYPE fw
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
#
|
||||
# Default parameters for FW
|
||||
#
|
||||
param set RTL_RETURN_ALT 100
|
||||
param set RTL_DESCEND_ALT 100
|
||||
param set RTL_LAND_DELAY -1
|
||||
|
||||
param set NAV_ACC_RAD 50
|
||||
|
||||
param set PE_VELNE_NOISE 0.3
|
||||
param set PE_VELD_NOISE 0.35
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.0
|
||||
fi
|
||||
|
||||
# This is the gimbal pass mixer
|
||||
set MIXER_AUX pass
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_OUT 1234
|
||||
set PWM_AUX_DISARMED 1500
|
||||
set PWM_AUX_MIN 1000
|
||||
set PWM_AUX_MAX 2000
|
||||
@@ -0,0 +1,83 @@
|
||||
#!nsh
|
||||
#
|
||||
# Script to configure control interface
|
||||
#
|
||||
|
||||
set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers
|
||||
|
||||
if [ $MIXER != none -a $MIXER != skip ]
|
||||
then
|
||||
#
|
||||
# Load main mixer
|
||||
#
|
||||
|
||||
# Use the mixer file
|
||||
set MIXER_FILE /etc/mixers/$MIXER.main.mix
|
||||
|
||||
set OUTPUT_DEV /dev/pwm_output0
|
||||
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/uavcan/esc
|
||||
fi
|
||||
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
echo "INFO [init] Mixer: $MIXER_FILE on $OUTPUT_DEV"
|
||||
else
|
||||
echo "ERROR [init] Error loading mixer: $MIXER_FILE"
|
||||
echo "ERROR:[init] Could not load mixer: $MIXER_FILE" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
unset MIXER_FILE
|
||||
else
|
||||
if [ $MIXER != skip ]
|
||||
then
|
||||
echo "ERROR [init] Mixer not defined"
|
||||
echo "ERROR [init] Mixer not defined" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
||||
then
|
||||
if [ $PWM_OUT != none ]
|
||||
then
|
||||
#
|
||||
# Set PWM output frequency
|
||||
#
|
||||
if [ $PWM_RATE != none ]
|
||||
then
|
||||
pwm rate -c $PWM_OUT -r $PWM_RATE
|
||||
fi
|
||||
|
||||
#
|
||||
# Set disarmed, min and max PWM values
|
||||
#
|
||||
if [ $PWM_DISARMED != none ]
|
||||
then
|
||||
pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
|
||||
fi
|
||||
if [ $PWM_MIN != none ]
|
||||
then
|
||||
pwm min -c $PWM_OUT -p $PWM_MIN
|
||||
fi
|
||||
if [ $PWM_MAX != none ]
|
||||
then
|
||||
pwm max -c $PWM_OUT -p $PWM_MAX
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $FAILSAFE != none ]
|
||||
then
|
||||
pwm failsafe -d $OUTPUT_DEV $FAILSAFE
|
||||
fi
|
||||
fi
|
||||
|
||||
unset PWM_OUT
|
||||
unset PWM_RATE
|
||||
unset PWM_MIN
|
||||
unset PWM_MAX
|
||||
unset FAILSAFE
|
||||
unset OUTPUT_DEV
|
||||
@@ -0,0 +1,17 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for multirotors:
|
||||
# att & pos estimator, att & pos control.
|
||||
#
|
||||
|
||||
|
||||
ekf2 start
|
||||
|
||||
mc_att_control start
|
||||
|
||||
mc_pos_control start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
#
|
||||
land_detector start multicopter
|
||||
@@ -0,0 +1,49 @@
|
||||
#!nsh
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set PE_VELNE_NOISE 0.5
|
||||
param set PE_VELD_NOISE 0.35
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.25
|
||||
|
||||
param set NAV_ACC_RAD 2.0
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
param set RTL_DESCEND_ALT 10.0
|
||||
param set PWM_DISARMED 900
|
||||
param set PWM_MIN 1075
|
||||
param set PWM_MAX 1950
|
||||
|
||||
param set RTL_LAND_DELAY 0
|
||||
fi
|
||||
|
||||
# set environment variables (!= parameters)
|
||||
set PWM_RATE 400
|
||||
# tell the mixer to use parameters for these instead
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
set PWM_MIN p:PWM_MIN
|
||||
set PWM_MAX p:PWM_MAX
|
||||
|
||||
# This is the gimbal pass mixer
|
||||
set MIXER_AUX pass
|
||||
set PWM_AUX_RATE 50
|
||||
set PWM_AUX_OUT 1234
|
||||
set PWM_AUX_DISARMED 1500
|
||||
set PWM_AUX_MIN 1000
|
||||
set PWM_AUX_MAX 2000
|
||||
|
||||
# Transitional support: ensure suitable PWM min/max param values
|
||||
if param compare PWM_MIN 1000
|
||||
then
|
||||
param set PWM_MIN 1075
|
||||
fi
|
||||
if param compare PWM_MAX 2000
|
||||
then
|
||||
param set PWM_MAX 1950
|
||||
fi
|
||||
if param compare PWM_DISARMED 0
|
||||
then
|
||||
param set PWM_DISARMED 900
|
||||
fi
|
||||
@@ -0,0 +1,46 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard startup script for TAP v1 onboard sensor drivers.
|
||||
#
|
||||
|
||||
if adc start
|
||||
then
|
||||
fi
|
||||
|
||||
# External I2C bus
|
||||
if hmc5883 -C -T -X start
|
||||
then
|
||||
fi
|
||||
|
||||
if lis3mdl -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus is rotated 90 deg yaw
|
||||
if hmc5883 -C -T -S -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
|
||||
if mpu6000 -R 2 -T 20608 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus mpu9250 is rotated 90 deg yaw
|
||||
if mpu9250 -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
if meas_airspeed start
|
||||
then
|
||||
fi
|
||||
|
||||
if sf1xx start
|
||||
then
|
||||
fi
|
||||
|
||||
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
|
||||
usleep 20000
|
||||
if sensors start
|
||||
then
|
||||
fi
|
||||
@@ -0,0 +1,24 @@
|
||||
#!nsh
|
||||
#
|
||||
# Standard apps for vtol:
|
||||
# att & pos estimator, att & pos control.
|
||||
#
|
||||
#
|
||||
|
||||
|
||||
#---------------------------------------
|
||||
# Estimator group selction
|
||||
#
|
||||
ekf2 start
|
||||
|
||||
vtol_att_control start
|
||||
mc_att_control start
|
||||
mc_pos_control start
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
#
|
||||
# Start Land Detector
|
||||
# Multicopter for now until we have something for VTOL
|
||||
#
|
||||
land_detector start vtol
|
||||
@@ -0,0 +1,49 @@
|
||||
#!nsh
|
||||
|
||||
set VEHICLE_TYPE vtol
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 6.0
|
||||
param set MC_PITCH_P 6.0
|
||||
param set MC_YAW_P 4
|
||||
|
||||
param set PE_VELNE_NOISE 0.5
|
||||
param set PE_VELD_NOISE 0.3
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.25
|
||||
param set PE_ABIAS_PNOISE 0.0001
|
||||
|
||||
#
|
||||
# Default parameters for mission and position handling
|
||||
#
|
||||
param set NAV_ACC_RAD 3
|
||||
param set MPC_TKO_SPEED 1.0
|
||||
param set MPC_LAND_SPEED 0.7
|
||||
param set MPC_Z_VEL_MAX 1.5
|
||||
param set MPC_XY_VEL_MAX 4.0
|
||||
param set MIS_YAW_TMT 10
|
||||
param set MPC_ACC_HOR_MAX 2.0
|
||||
param set RTL_LAND_DELAY 0
|
||||
fi
|
||||
|
||||
# set environment variables (!= parameters)
|
||||
set PWM_RATE 400
|
||||
# tell the mixer to use parameters for these instead
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
set PWM_MIN p:PWM_MIN
|
||||
set PWM_MAX p:PWM_MAX
|
||||
|
||||
# Transitional support: ensure suitable PWM min/max param values
|
||||
if param compare PWM_MIN 1000
|
||||
then
|
||||
param set PWM_MIN 1075
|
||||
fi
|
||||
if param compare PWM_MAX 2000
|
||||
then
|
||||
param set PWM_MAX 1950
|
||||
fi
|
||||
if param compare PWM_DISARMED 0
|
||||
then
|
||||
param set PWM_DISARMED 900
|
||||
fi
|
||||
@@ -0,0 +1,486 @@
|
||||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script.
|
||||
#
|
||||
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
|
||||
#
|
||||
|
||||
#
|
||||
# Start CDC/ACM serial driver
|
||||
#
|
||||
sercon
|
||||
|
||||
#
|
||||
# Default to auto-start mode.
|
||||
#
|
||||
set MODE autostart
|
||||
|
||||
set TUNE_ERR ML<<CP4CP4CP4CP4CP4
|
||||
set LOG_FILE /fs/microsd/bootlog.txt
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
# REBOOTWORK this needs to start after the flight control loop
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
tone_alarm MBAGP
|
||||
if mkfatfs /dev/mmcsd0
|
||||
then
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "INFO [init] MicroSD card formatted"
|
||||
else
|
||||
echo "ERROR [init] Format failed"
|
||||
tone_alarm MNBG
|
||||
set LOG_FILE /dev/null
|
||||
fi
|
||||
else
|
||||
set LOG_FILE /dev/null
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
# Disable autostart if the script found.
|
||||
#
|
||||
set FRC /fs/microsd/etc/rc.txt
|
||||
if [ -f $FRC ]
|
||||
then
|
||||
echo "INFO [init] Executing script: $FRC"
|
||||
sh $FRC
|
||||
set MODE custom
|
||||
fi
|
||||
unset FRC
|
||||
|
||||
if [ $MODE == autostart ]
|
||||
then
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Load parameters
|
||||
#
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
if mtd start
|
||||
then
|
||||
set PARAM_FILE /fs/mtd_params
|
||||
fi
|
||||
|
||||
param select $PARAM_FILE
|
||||
if param load
|
||||
then
|
||||
else
|
||||
if param reset
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start system state indicator
|
||||
#
|
||||
if rgbled start
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Set AUTOCNF flag to use it in AUTOSTART scripts
|
||||
#
|
||||
if param compare SYS_AUTOCONFIG 1
|
||||
then
|
||||
# Wipe out params except RC*
|
||||
param reset_nostart RC*
|
||||
set AUTOCNF yes
|
||||
else
|
||||
set AUTOCNF no
|
||||
fi
|
||||
|
||||
#
|
||||
# Set default values
|
||||
#
|
||||
set VEHICLE_TYPE none
|
||||
set MIXER none
|
||||
set OUTPUT_MODE none
|
||||
set PWM_OUT none
|
||||
set PWM_RATE none
|
||||
set PWM_DISARMED none
|
||||
set PWM_MIN none
|
||||
set PWM_MAX none
|
||||
set FMU_MODE pwm
|
||||
set MAVLINK_F default
|
||||
set EXIT_ON_END no
|
||||
set MAV_TYPE none
|
||||
set FAILSAFE none
|
||||
set USE_IO no
|
||||
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
echo "INFO [init] No autostart"
|
||||
else
|
||||
sh /etc/init.d/rc.autostart
|
||||
fi
|
||||
unset MODE
|
||||
|
||||
#
|
||||
# If autoconfig parameter was set, reset it and save parameters
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set SYS_AUTOCONFIG 0
|
||||
param save
|
||||
fi
|
||||
unset AUTOCNF
|
||||
|
||||
#
|
||||
# Set default output if not set
|
||||
#
|
||||
if [ $OUTPUT_MODE == none ]
|
||||
then
|
||||
if [ $USE_IO == yes ]
|
||||
then
|
||||
set OUTPUT_MODE io
|
||||
else
|
||||
set OUTPUT_MODE fmu
|
||||
fi
|
||||
fi
|
||||
|
||||
gps start -d /dev/ttyS0
|
||||
|
||||
# waypoint storage
|
||||
# REBOOTWORK this needs to start in parallel
|
||||
if dataman start
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Sensors System (start before Commander so Preflight checks are properly run)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start CPU load monitor
|
||||
#
|
||||
load_mon start
|
||||
|
||||
#
|
||||
# Start primary output
|
||||
#
|
||||
set TTYS1_BUSY no
|
||||
|
||||
#
|
||||
# Check if UAVCAN is enabled, default to it for ESCs
|
||||
#
|
||||
if param greater UAVCAN_ENABLE 2
|
||||
then
|
||||
set OUTPUT_MODE uavcan_esc
|
||||
fi
|
||||
|
||||
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
|
||||
if [ $OUTPUT_MODE != none ]
|
||||
then
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
then
|
||||
if param compare UAVCAN_ENABLE 0
|
||||
then
|
||||
echo "INFO [init] OVERRIDING UAVCAN_ENABLE = 1" >> $LOG_FILE
|
||||
param set UAVCAN_ENABLE 1
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu ]
|
||||
then
|
||||
if fmu mode_$FMU_MODE
|
||||
then
|
||||
else
|
||||
echo "ERR [init] FMU start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
if fmu mode_pwm4
|
||||
then
|
||||
else
|
||||
echo "ERROR [init] FMU mode_$FMU_MODE start failed" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
mavlink start -r 1200 -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Starting stuff according to UAVCAN_ENABLE value
|
||||
#
|
||||
if param greater UAVCAN_ENABLE 0
|
||||
then
|
||||
if uavcan start
|
||||
then
|
||||
else
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
if param greater UAVCAN_ENABLE 1
|
||||
then
|
||||
if uavcan start fw
|
||||
then
|
||||
else
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Optional drivers
|
||||
#
|
||||
|
||||
# Sensors on the PWM interface bank
|
||||
if param compare SENS_EN_LL40LS 1
|
||||
then
|
||||
if pwm_input start
|
||||
then
|
||||
if ll40ls start pwm
|
||||
then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
# sf0x lidar sensor
|
||||
if param compare SENS_EN_SF0X 1
|
||||
then
|
||||
sf0x start
|
||||
fi
|
||||
|
||||
# Start USB shell if no microSD present, MAVLink else
|
||||
if [ $LOG_FILE == /dev/null ]
|
||||
then
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
else
|
||||
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
|
||||
fi
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
if param compare SYS_LOGGER 0
|
||||
then
|
||||
if sdlog2 start -r 100 -a -b 9 -t
|
||||
then
|
||||
fi
|
||||
else
|
||||
if logger start -b 12 -t
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Fixed wing setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == fw ]
|
||||
then
|
||||
echo "INFO [init] Fixedwing"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
# Set default mixer for fixed wing if not defined
|
||||
set MIXER AERT
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use MAV_TYPE = 1 (fixed wing) if not defined
|
||||
set MAV_TYPE 1
|
||||
fi
|
||||
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard fixedwing apps
|
||||
sh /etc/init.d/rc.fw_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Multicopters setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == mc ]
|
||||
then
|
||||
echo "INFO [init] Multicopter"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
echo "INFO [init] Mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == quad_x -o $MIXER == quad_+ ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == quad_w ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == quad_h ]
|
||||
then
|
||||
set MAV_TYPE 2
|
||||
fi
|
||||
if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
|
||||
then
|
||||
set MAV_TYPE 15
|
||||
fi
|
||||
if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == hexa_cox ]
|
||||
then
|
||||
set MAV_TYPE 13
|
||||
fi
|
||||
if [ $MIXER == octo_x -o $MIXER == octo_+ ]
|
||||
then
|
||||
set MAV_TYPE 14
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 2
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
fi
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard multicopter apps
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# VTOL setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == vtol ]
|
||||
then
|
||||
echo "INFO [init] VTOL"
|
||||
|
||||
if [ $MIXER == none ]
|
||||
then
|
||||
echo "WARN [init] VTOL mixer undefined"
|
||||
fi
|
||||
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
# Use mixer to detect vehicle type
|
||||
if [ $MIXER == caipirinha_vtol ]
|
||||
then
|
||||
set MAV_TYPE 19
|
||||
fi
|
||||
if [ $MIXER == firefly6 ]
|
||||
then
|
||||
set MAV_TYPE 21
|
||||
fi
|
||||
if [ $MIXER == quad_x_pusher_vtol ]
|
||||
then
|
||||
set MAV_TYPE 22
|
||||
fi
|
||||
fi
|
||||
|
||||
# Still no MAV_TYPE found
|
||||
if [ $MAV_TYPE == none ]
|
||||
then
|
||||
echo "WARN [init] Unknown MAV_TYPE"
|
||||
param set MAV_TYPE 19
|
||||
else
|
||||
param set MAV_TYPE $MAV_TYPE
|
||||
fi
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard vtol apps
|
||||
sh /etc/init.d/rc.vtol_apps
|
||||
fi
|
||||
|
||||
#
|
||||
# Rover setup
|
||||
#
|
||||
if [ $VEHICLE_TYPE == rover ]
|
||||
then
|
||||
# 10 is MAV_TYPE_GROUND_ROVER
|
||||
set MAV_TYPE 10
|
||||
|
||||
# Load mixer and configure outputs
|
||||
sh /etc/init.d/rc.interface
|
||||
|
||||
# Start standard rover apps
|
||||
sh /etc/init.d/rc.axialracing_ax10_apps
|
||||
|
||||
param set MAV_TYPE 10
|
||||
fi
|
||||
|
||||
unset MIXER
|
||||
unset MAV_TYPE
|
||||
unset OUTPUT_MODE
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
navigator start
|
||||
|
||||
#
|
||||
# Generic setup (autostart ID not found)
|
||||
#
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "WARN [init] No autostart ID found"
|
||||
fi
|
||||
|
||||
# Start any custom addons
|
||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||
if [ -f $FEXTRAS ]
|
||||
then
|
||||
echo "INFO [init] Addons script: $FEXTRAS"
|
||||
sh $FEXTRAS
|
||||
fi
|
||||
unset FEXTRAS
|
||||
|
||||
# Run no SD alarm
|
||||
if [ $LOG_FILE == /dev/null ]
|
||||
then
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
# End of autostart
|
||||
fi
|
||||
|
||||
# There is no further script processing, so we can free some RAM
|
||||
# XXX potentially unset all script variables.
|
||||
unset TUNE_ERR
|
||||
|
||||
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
|
||||
mavlink boot_complete
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
echo "INFO [init] NSH exit"
|
||||
exit
|
||||
fi
|
||||
unset EXIT_ON_END
|
||||
@@ -0,0 +1,105 @@
|
||||
## PX4 mixer definitions ##
|
||||
|
||||
Files in this directory implement example mixers that can be used as a basis
|
||||
for customisation, or for general testing purposes.
|
||||
|
||||
For a detailed description of the mixing architecture and examples see:
|
||||
http://px4.io/dev/mixing
|
||||
|
||||
### Syntax ###
|
||||
|
||||
Mixer definitions are text files; lines beginning with a single capital letter
|
||||
followed by a colon are significant. All other lines are ignored, meaning that
|
||||
explanatory text can be freely mixed with the definitions.
|
||||
|
||||
Each file may define more than one mixer; the allocation of mixers to actuators
|
||||
is specific to the device reading the mixer definition, and the number of
|
||||
actuator outputs generated by a mixer is specific to the mixer.
|
||||
|
||||
For example: each simple or null mixer is assigned to outputs 1 to x
|
||||
in the order they appear in the mixer file.
|
||||
|
||||
A mixer begins with a line of the form
|
||||
|
||||
<tag>: <mixer arguments>
|
||||
|
||||
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
|
||||
multirotor mixer, etc.
|
||||
|
||||
#### Null Mixer ####
|
||||
|
||||
A null mixer consumes no controls and generates a single actuator output whose
|
||||
value is always zero. Typically a null mixer is used as a placeholder in a
|
||||
collection of mixers in order to achieve a specific pattern of actuator outputs.
|
||||
|
||||
The null mixer definition has the form:
|
||||
|
||||
Z:
|
||||
|
||||
#### Simple Mixer ####
|
||||
|
||||
A simple mixer combines zero or more control inputs into a single actuator
|
||||
output. Inputs are scaled, and the mixing function sums the result before
|
||||
applying an output scaler.
|
||||
|
||||
A simple mixer definition begins with:
|
||||
|
||||
M: <control count>
|
||||
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
If <control count> is zero, the sum is effectively zero and the mixer will
|
||||
output a fixed value that is <offset> constrained by <lower limit> and <upper
|
||||
limit>.
|
||||
|
||||
The second line defines the output scaler with scaler parameters as discussed
|
||||
above. Whilst the calculations are performed as floating-point operations, the
|
||||
values stored in the definition file are scaled by a factor of 10000; i.e. an
|
||||
offset of -0.5 is encoded as -5000.
|
||||
|
||||
The definition continues with <control count> entries describing the control
|
||||
inputs and their scaling, in the form:
|
||||
|
||||
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
|
||||
|
||||
The <group> value identifies the control group from which the scaler will read,
|
||||
and the <index> value an offset within that group. These values are specific to
|
||||
the device reading the mixer definition.
|
||||
|
||||
When used to mix vehicle controls, mixer group zero is the vehicle attitude
|
||||
control group, and index values zero through three are normally roll, pitch,
|
||||
yaw and thrust respectively.
|
||||
|
||||
The remaining fields on the line configure the control scaler with parameters as
|
||||
discussed above. Whilst the calculations are performed as floating-point
|
||||
operations, the values stored in the definition file are scaled by a factor of
|
||||
10000; i.e. an offset of -0.5 is encoded as -5000.
|
||||
|
||||
#### Multirotor Mixer ####
|
||||
|
||||
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
|
||||
into a set of actuator outputs intended to drive motor speed controllers.
|
||||
|
||||
The mixer definition is a single line of the form:
|
||||
|
||||
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
|
||||
|
||||
The supported geometries include:
|
||||
|
||||
* 4x - quadrotor in X configuration
|
||||
* 4+ - quadrotor in + configuration
|
||||
* 6x - hexcopter in X configuration
|
||||
* 6+ - hexcopter in + configuration
|
||||
* 8x - octocopter in X configuration
|
||||
* 8+ - octocopter in + configuration
|
||||
|
||||
Each of the roll, pitch and yaw scale values determine scaling of the roll,
|
||||
pitch and yaw controls relative to the thrust control. Whilst the calculations
|
||||
are performed as floating-point operations, the values stored in the definition
|
||||
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
|
||||
|
||||
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
|
||||
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
|
||||
range -1.0 to 1.0.
|
||||
|
||||
In the case where an actuator saturates, all actuator values are rescaled so that
|
||||
the saturating actuator is limited to 1.0.
|
||||
@@ -0,0 +1,3 @@
|
||||
# Hexa X
|
||||
|
||||
R: 6x 10000 10000 10000 0
|
||||
@@ -0,0 +1,7 @@
|
||||
R: 4x 10000 10000 10000 0
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 3 5 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 3 6 10000 10000 0 -10000 10000
|
||||
@@ -1,9 +0,0 @@
|
||||
QGC WPL 110
|
||||
0 1 0 16 0 0 0 0 47.3979949951 8.54559612274 25.0 1
|
||||
1 0 2 3000 4.0 0.0 0.0 0.0 47.3980331421 8.54578971863 25.0 1
|
||||
2 0 3 16 0.0 0.0 -0.0 0.0 47.399269104 8.54557228088 25.0 1
|
||||
3 0 3 16 0.0 0.0 -0.0 0.0 47.3992652893 8.54230213165 25.0 1
|
||||
4 0 3 16 0.0 0.0 -0.0 0.0 47.3974761963 8.54239082336 25.0 1
|
||||
5 0 3 16 0.0 0.0 -0.0 0.0 47.3976669312 8.54509449005 25.0 1
|
||||
6 0 2 3000 3.0 0.0 0.0 0.0 47.3977851868 8.54526233673 25.0 1
|
||||
7 0 3 21 25.0 0.0 -0.0 0.0 47.3979797363 8.54460906982 25.0 1
|
||||
@@ -23,3 +23,7 @@ do
|
||||
adb push $arg $last
|
||||
((i+=1))
|
||||
done
|
||||
|
||||
# Make sure they are synced to the file system
|
||||
echo "Syncing FS..."
|
||||
adb shell sync
|
||||
|
||||
Executable
+39
@@ -0,0 +1,39 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [ -z ${BEBOP_IP+x} ]; then
|
||||
ip=192.168.42.1
|
||||
echo "\$BEBOP_IP is not set (use default: $ip)"
|
||||
else
|
||||
ip=$BEBOP_IP
|
||||
echo "\$BEBOP_IP is set to $ip"
|
||||
fi
|
||||
port=9050
|
||||
|
||||
echo "Connecting to bebop: $ip:$port"
|
||||
|
||||
# adb returns also 0 as exit status if the connection fails
|
||||
adb_return=$(adb connect $ip:$port)
|
||||
adb_status=$(echo $adb_return | cut -f 1 -d " ")
|
||||
|
||||
if [[ $adb_status == "unable" ]]; then
|
||||
|
||||
echo ""
|
||||
echo "Connection with Parrot Bebop could not be established:"
|
||||
echo " Make sure you are connected with the Bebop's WiFi and"
|
||||
echo " enable access to the board by pressing the power button 4 times."
|
||||
echo ""
|
||||
exit 50
|
||||
|
||||
fi
|
||||
|
||||
echo "Connection successfully established"
|
||||
|
||||
sleep 1
|
||||
|
||||
adb shell mount -o remount,rw /
|
||||
adb shell touch /home/root/parameters
|
||||
|
||||
../Tools/adb_upload.sh $@
|
||||
|
||||
echo "Disconnecting from bebop"
|
||||
adb disconnect
|
||||
+20
-67
@@ -1,70 +1,23 @@
|
||||
#!/usr/bin/env bash
|
||||
set -eu
|
||||
failed=0
|
||||
for fn in $(find src/examples \
|
||||
src/systemcmds \
|
||||
src/include \
|
||||
src/drivers \
|
||||
src/platforms \
|
||||
src/firmware \
|
||||
src/lib/launchdetection \
|
||||
src/lib/geo \
|
||||
src/lib/geo_lookup \
|
||||
src/lib/conversion \
|
||||
src/lib/rc \
|
||||
src/lib/version \
|
||||
src/modules/attitude_estimator_q \
|
||||
src/modules/fw_att_control \
|
||||
src/modules/gpio_led \
|
||||
src/modules/land_detector \
|
||||
src/modules/muorb \
|
||||
src/modules/px4iofirmware \
|
||||
src/modules/param \
|
||||
src/modules/sensors \
|
||||
src/modules/simulator \
|
||||
src/modules/uORB \
|
||||
src/modules/bottle_drop \
|
||||
src/modules/dataman \
|
||||
src/modules/segway \
|
||||
src/modules/local_position_estimator \
|
||||
src/modules/unit_test \
|
||||
src/modules/systemlib \
|
||||
src/lib/controllib \
|
||||
-path './Build' -prune -o \
|
||||
-path './mavlink' -prune -o \
|
||||
-path './NuttX' -prune -o \
|
||||
-path './src/lib/eigen' -prune -o \
|
||||
-path './src/modules/uavcan/libuavcan' -prune -o \
|
||||
-path './src/modules/attitude_estimator_ekf/codegen' -prune -o \
|
||||
-path './src/modules/ekf_att_pos_estimator' -prune -o \
|
||||
-path './src/modules/sdlog2' -prune -o \
|
||||
-path './src/modules/uORB' -prune -o \
|
||||
-path './src/modules/vtol_att_control' -prune -o \
|
||||
-path './unittests/build' -prune -o \
|
||||
-path './unittests/gtest' -prune -o \
|
||||
-name '*.c' -o -name '*.cpp' -o -name '*.hpp' -o -name '*.h' \
|
||||
-not -name '*generated*' \
|
||||
-not -name '*uthash.h' \
|
||||
-not -name '*utstring.h' \
|
||||
-not -name '*utlist.h' \
|
||||
-not -name '*utarray.h' \
|
||||
-type f); do
|
||||
if [ -f "$fn" ];
|
||||
then
|
||||
./Tools/fix_code_style.sh --quiet < $fn > $fn.pretty
|
||||
diffsize=$(diff -y --suppress-common-lines $fn $fn.pretty | wc -l)
|
||||
rm -f $fn.pretty
|
||||
if [ $diffsize -ne 0 ]; then
|
||||
failed=1
|
||||
echo $fn 'bad formatting, please run "./Tools/fix_code_style.sh' $fn'"'
|
||||
fi
|
||||
fi
|
||||
done
|
||||
|
||||
if [ $failed -eq 0 ]; then
|
||||
echo "Format checks passed"
|
||||
exit 0
|
||||
else
|
||||
echo "Format checks failed"
|
||||
exit 1
|
||||
file=$1
|
||||
|
||||
DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
|
||||
|
||||
if [ -f "$file" ];
|
||||
then
|
||||
${DIR}/fix_code_style.sh --dry-run $file | grep --quiet Formatted
|
||||
if [[ $? -eq 0 ]]
|
||||
then
|
||||
${DIR}/fix_code_style.sh --quiet < $file > $file.pretty
|
||||
|
||||
echo
|
||||
git --no-pager diff --no-index --minimal --histogram --color=always $file $file.pretty
|
||||
echo
|
||||
|
||||
rm -f $file.pretty
|
||||
echo $file 'bad formatting, please run "./Tools/fix_code_style.sh' $file'"'
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
|
||||
Executable
+57
@@ -0,0 +1,57 @@
|
||||
#!/usr/bin/env bash
|
||||
set -eu
|
||||
failed=0
|
||||
|
||||
DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
|
||||
|
||||
find \
|
||||
src/drivers \
|
||||
src/examples \
|
||||
src/firmware \
|
||||
src/include \
|
||||
src/lib/controllib \
|
||||
src/lib/conversion \
|
||||
src/lib/geo \
|
||||
src/lib/geo_lookup \
|
||||
src/lib/launchdetection \
|
||||
src/lib/rc \
|
||||
src/lib/tailsitter_recovery \
|
||||
src/lib/terrain_estimation \
|
||||
src/lib/version \
|
||||
src/modules/attitude_estimator_q \
|
||||
src/modules/bottle_drop \
|
||||
src/modules/controllib_test \
|
||||
src/modules/dataman \
|
||||
src/modules/fw_att_control \
|
||||
src/modules/fw_pos_control_l1 \
|
||||
src/modules/gpio_led \
|
||||
src/modules/land_detector \
|
||||
src/modules/local_position_estimator \
|
||||
src/modules/logger \
|
||||
src/modules/mavlink/mavlink_tests \
|
||||
src/modules/muorb \
|
||||
src/modules/param \
|
||||
src/modules/px4iofirmware \
|
||||
src/modules/replay \
|
||||
src/modules/segway \
|
||||
src/modules/sensors \
|
||||
src/modules/simulator \
|
||||
src/modules/systemlib \
|
||||
src/modules/unit_test \
|
||||
src/modules/uORB \
|
||||
src/modules/vtol_att_control \
|
||||
src/platforms \
|
||||
src/systemcmds \
|
||||
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) \
|
||||
-not -name '*generated.h' \
|
||||
-not -name '*uthash.h' \
|
||||
-not -name '*utstring.h' \
|
||||
-not -name '*utlist.h' \
|
||||
-not -name '*utarray.h' \
|
||||
-print0 | xargs -0 -n 1 -P 8 -I % ${DIR}/check_code_style.sh %
|
||||
|
||||
|
||||
if [ $? -eq 0 ]; then
|
||||
echo "Format checks passed"
|
||||
exit 0
|
||||
fi
|
||||
@@ -69,6 +69,7 @@ check_git_submodule Tools/jMAVSim
|
||||
check_git_submodule Tools/sitl_gazebo
|
||||
check_git_submodule cmake/cmake_hexagon
|
||||
check_git_submodule mavlink/include/mavlink/v1.0
|
||||
check_git_submodule mavlink/include/mavlink/v2.0
|
||||
check_git_submodule src/lib/DriverFramework
|
||||
check_git_submodule src/lib/DriverFramework/cmake/cmake_hexagon
|
||||
check_git_submodule src/lib/DriverFramework/dspal
|
||||
|
||||
@@ -43,10 +43,10 @@ import subprocess
|
||||
# If the following lines were pasted into the shell after running decode_backtrace.py
|
||||
#
|
||||
# INFO Backtrace: 10
|
||||
# INFO ./mainapp(px4_backtrace+0x27) [0x42b212]
|
||||
# INFO ./mainapp() [0x42d608]
|
||||
# INFO ./mainapp() [0x42d57e]
|
||||
# INFO ./mainapp() [0x4ba48d]
|
||||
# INFO ./px4(px4_backtrace+0x27) [0x42b212]
|
||||
# INFO ./px4() [0x42d608]
|
||||
# INFO ./px4() [0x42d57e]
|
||||
# INFO ./px4() [0x4ba48d]
|
||||
#
|
||||
# The output would be:
|
||||
#
|
||||
@@ -63,7 +63,7 @@ def usage():
|
||||
msg = """
|
||||
Usage: Tools/decode_backtrace.py <builddir>
|
||||
|
||||
This will load the symbols for <builddir>/src/firmware/posix/mainapp
|
||||
This will load the symbols for <builddir>/src/firmware/posix/px4
|
||||
The user just needs to copy and paste the backtrace into the terminal
|
||||
where decode_backtrace.py is running.
|
||||
|
||||
@@ -75,7 +75,7 @@ func = []
|
||||
|
||||
# Load the symbols from the binary
|
||||
def load_symbol_map():
|
||||
output = subprocess.check_output(["nm", "-p", "-C", os.sys.argv[1]+"/src/firmware/posix/mainapp"])
|
||||
output = subprocess.check_output(["nm", "-p", "-C", os.sys.argv[1]+"/src/firmware/posix/px4"])
|
||||
data = output.split("\n")
|
||||
data.sort()
|
||||
|
||||
|
||||
@@ -115,7 +115,6 @@ print("""
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#define __STDC_FORMAT_MACROS
|
||||
#include <inttypes.h>
|
||||
|
||||
#ifndef PRIu64
|
||||
@@ -173,6 +172,7 @@ for index,m in enumerate(messages[1:]):
|
||||
print("\t\t\ti++;")
|
||||
print("\t\t\tprintf(\"\\nTOPIC: %s #%%d\\n\", i);" % m)
|
||||
print("\t\t\torb_copy(ID,sub,&container);")
|
||||
print("\t\t\tprintf(\"timestamp: %\" PRIu64 \"\\n\", container.timestamp);")
|
||||
for item in message_elements[index+1]:
|
||||
if item[0] == "float":
|
||||
print("\t\t\tprintf(\"%s: %%8.4f\\n\",(double)container.%s);" % (item[1], item[1]))
|
||||
|
||||
+1
-1
Submodule Tools/jMAVSim updated: 9155c8f955...a5b0f1f089
Executable
+206
@@ -0,0 +1,206 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
"""
|
||||
Open a shell over MAVLink.
|
||||
|
||||
@author: Beat Kueng (beat-kueng@gmx.net)
|
||||
"""
|
||||
|
||||
|
||||
from __future__ import print_function
|
||||
import sys, select
|
||||
import termios
|
||||
|
||||
try:
|
||||
from pymavlink import mavutil
|
||||
import serial
|
||||
except:
|
||||
print("Failed to import pymavlink.")
|
||||
print("You may need to install it with 'pip install pymavlink pyserial'")
|
||||
exit(-1)
|
||||
from argparse import ArgumentParser
|
||||
|
||||
|
||||
class MavlinkSerialPort():
|
||||
'''an object that looks like a serial port, but
|
||||
transmits using mavlink SERIAL_CONTROL packets'''
|
||||
def __init__(self, portname, baudrate, devnum=0, debug=0):
|
||||
self.baudrate = 0
|
||||
self._debug = debug
|
||||
self.buf = ''
|
||||
self.port = devnum
|
||||
self.debug("Connecting with MAVLink to %s ..." % portname)
|
||||
self.mav = mavutil.mavlink_connection(portname, autoreconnect=True, baud=baudrate)
|
||||
self.mav.wait_heartbeat()
|
||||
self.debug("HEARTBEAT OK\n")
|
||||
self.debug("Locked serial device\n")
|
||||
|
||||
def debug(self, s, level=1):
|
||||
'''write some debug text'''
|
||||
if self._debug >= level:
|
||||
print(s)
|
||||
|
||||
def write(self, b):
|
||||
'''write some bytes'''
|
||||
self.debug("sending '%s' (0x%02x) of len %u\n" % (b, ord(b[0]), len(b)), 2)
|
||||
while len(b) > 0:
|
||||
n = len(b)
|
||||
if n > 70:
|
||||
n = 70
|
||||
buf = [ord(x) for x in b[:n]]
|
||||
buf.extend([0]*(70-len(buf)))
|
||||
self.mav.mav.serial_control_send(self.port,
|
||||
mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
|
||||
mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND,
|
||||
0,
|
||||
0,
|
||||
n,
|
||||
buf)
|
||||
b = b[n:]
|
||||
|
||||
def close(self):
|
||||
self.mav.mav.serial_control_send(self.port, 0, 0, 0, 0, [0]*70)
|
||||
|
||||
def _recv(self):
|
||||
'''read some bytes into self.buf'''
|
||||
m = self.mav.recv_match(condition='SERIAL_CONTROL.count!=0',
|
||||
type='SERIAL_CONTROL', blocking=True,
|
||||
timeout=0.03)
|
||||
if m is not None:
|
||||
if self._debug > 2:
|
||||
print(m)
|
||||
data = m.data[:m.count]
|
||||
self.buf += ''.join(str(chr(x)) for x in data)
|
||||
|
||||
def read(self, n):
|
||||
'''read some bytes'''
|
||||
if len(self.buf) == 0:
|
||||
self._recv()
|
||||
if len(self.buf) > 0:
|
||||
if n > len(self.buf):
|
||||
n = len(self.buf)
|
||||
ret = self.buf[:n]
|
||||
self.buf = self.buf[n:]
|
||||
if self._debug >= 2:
|
||||
for b in ret:
|
||||
self.debug("read 0x%x" % ord(b), 2)
|
||||
return ret
|
||||
return ''
|
||||
|
||||
|
||||
def main():
|
||||
parser = ArgumentParser(description=__doc__)
|
||||
parser.add_argument('port', metavar='PORT', nargs='?', default = None,
|
||||
help='Mavlink port name: serial: DEVICE[,BAUD], udp: IP:PORT, tcp: tcp:IP:PORT. Eg: \
|
||||
/dev/ttyUSB0 or 0.0.0.0:14550. Auto-detect serial if not given.')
|
||||
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int,
|
||||
help="Mavlink port baud rate (default=115200)", default=115200)
|
||||
args = parser.parse_args()
|
||||
|
||||
|
||||
if args.port == None:
|
||||
serial_list = mavutil.auto_detect_serial(preferred_list=['*FTDI*',
|
||||
"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*'])
|
||||
|
||||
if len(serial_list) == 0:
|
||||
print("Error: no serial connection found")
|
||||
return
|
||||
|
||||
if len(serial_list) > 1:
|
||||
print('Auto-detected serial ports are:')
|
||||
for port in serial_list:
|
||||
print(" {:}".format(port))
|
||||
print('Using port {:}'.format(serial_list[0]))
|
||||
args.port = serial_list[0].device
|
||||
|
||||
|
||||
print("Connecting to MAVLINK...")
|
||||
mav_serialport = MavlinkSerialPort(args.port, args.baudrate, devnum=10)
|
||||
|
||||
mav_serialport.write('\n') # make sure the shell is started
|
||||
|
||||
# setup the console, so we can read one char at a time
|
||||
fd_in = sys.stdin.fileno()
|
||||
old_attr = termios.tcgetattr(fd_in)
|
||||
new_attr = termios.tcgetattr(fd_in)
|
||||
new_attr[3] = new_attr[3] & ~termios.ECHO # lflags
|
||||
new_attr[3] = new_attr[3] & ~termios.ICANON
|
||||
|
||||
try:
|
||||
termios.tcsetattr(fd_in, termios.TCSANOW, new_attr)
|
||||
cur_line = ''
|
||||
command_history = []
|
||||
cur_history_index = 0
|
||||
|
||||
def erase_last_n_chars(N):
|
||||
if N == 0: return
|
||||
CURSOR_BACK_N = '\x1b['+str(N)+'D'
|
||||
ERASE_END_LINE = '\x1b[K'
|
||||
sys.stdout.write(CURSOR_BACK_N + ERASE_END_LINE)
|
||||
|
||||
while True:
|
||||
while True:
|
||||
i, o, e = select.select([sys.stdin], [], [], 0)
|
||||
if not i: break
|
||||
ch = sys.stdin.read(1)
|
||||
|
||||
# provide a simple shell with command history
|
||||
if ch == '\n':
|
||||
if len(cur_line) > 0:
|
||||
# erase current text (mavlink shell will echo it as well)
|
||||
erase_last_n_chars(len(cur_line))
|
||||
|
||||
# add to history
|
||||
if len(command_history) == 0 or command_history[-1] != cur_line:
|
||||
command_history.append(cur_line)
|
||||
if len(command_history) > 50:
|
||||
del command_history[0]
|
||||
cur_history_index = len(command_history)
|
||||
mav_serialport.write(cur_line+'\n')
|
||||
cur_line = ''
|
||||
elif ord(ch) == 127: # backslash
|
||||
if len(cur_line) > 0:
|
||||
erase_last_n_chars(1)
|
||||
cur_line = cur_line[:-1]
|
||||
sys.stdout.write(ch)
|
||||
elif ord(ch) == 033:
|
||||
ch = sys.stdin.read(1) # skip one
|
||||
ch = sys.stdin.read(1)
|
||||
if ch == 'A': # arrow up
|
||||
if cur_history_index > 0:
|
||||
cur_history_index -= 1
|
||||
elif ch == 'B': # arrow down
|
||||
if cur_history_index < len(command_history):
|
||||
cur_history_index += 1
|
||||
# TODO: else: support line editing
|
||||
|
||||
erase_last_n_chars(len(cur_line))
|
||||
if cur_history_index == len(command_history):
|
||||
cur_line = ''
|
||||
else:
|
||||
cur_line = command_history[cur_history_index]
|
||||
sys.stdout.write(cur_line)
|
||||
|
||||
elif ord(ch) > 3:
|
||||
cur_line += ch
|
||||
sys.stdout.write(ch)
|
||||
sys.stdout.flush()
|
||||
|
||||
data = mav_serialport.read(4096)
|
||||
if data and len(data) > 0:
|
||||
sys.stdout.write(data)
|
||||
sys.stdout.flush()
|
||||
|
||||
except serial.serialutil.SerialException as e:
|
||||
print(e)
|
||||
|
||||
except KeyboardInterrupt:
|
||||
mav_serialport.close()
|
||||
|
||||
finally:
|
||||
termios.tcsetattr(fd_in, termios.TCSADRAIN, old_attr)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
|
||||
@@ -69,6 +69,8 @@ class XMLOutput():
|
||||
xml_group.attrib["image"] = "VTOLTiltRotor"
|
||||
elif (group.GetName() == "Coaxial Helicopter"):
|
||||
xml_group.attrib["image"] = "HelicopterCoaxial"
|
||||
elif (group.GetName() == "Helicopter"):
|
||||
xml_group.attrib["image"] = "Helicopter"
|
||||
elif (group.GetName() == "Hexarotor Coaxial"):
|
||||
xml_group.attrib["image"] = "Y6A"
|
||||
elif (group.GetName() == "Y6B"):
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
import sys
|
||||
import re
|
||||
import math
|
||||
|
||||
global default_var
|
||||
default_var = {}
|
||||
|
||||
@@ -39,7 +41,7 @@ class Parameter(object):
|
||||
|
||||
# Define sorting order of the fields
|
||||
priority = {
|
||||
"board": 9,
|
||||
"board": 9,
|
||||
"short_desc": 8,
|
||||
"long_desc": 7,
|
||||
"min": 5,
|
||||
@@ -52,6 +54,7 @@ class Parameter(object):
|
||||
def __init__(self, name, type, default = ""):
|
||||
self.fields = {}
|
||||
self.values = {}
|
||||
self.bitmask = {}
|
||||
self.name = name
|
||||
self.type = type
|
||||
self.default = default
|
||||
@@ -77,6 +80,12 @@ class Parameter(object):
|
||||
"""
|
||||
self.values[code] = value
|
||||
|
||||
def SetBitmaskBit(self, index, bit):
|
||||
"""
|
||||
Set named enum value
|
||||
"""
|
||||
self.bitmask[index] = bit
|
||||
|
||||
def GetFieldCodes(self):
|
||||
"""
|
||||
Return list of existing field codes in convenient order
|
||||
@@ -115,6 +124,24 @@ class Parameter(object):
|
||||
return ""
|
||||
return fv
|
||||
|
||||
def GetBitmaskList(self):
|
||||
"""
|
||||
Return list of existing bitmask codes in convenient order
|
||||
"""
|
||||
keys = self.bitmask.keys()
|
||||
keys.sort(key=float)
|
||||
return keys
|
||||
|
||||
def GetBitmaskBit(self, index):
|
||||
"""
|
||||
Return value of the given bitmask code or None if not found.
|
||||
"""
|
||||
fv = self.bitmask.get(index)
|
||||
if not fv:
|
||||
# required because python 3 sorted does not accept None
|
||||
return ""
|
||||
return fv
|
||||
|
||||
class SourceParser(object):
|
||||
"""
|
||||
Parses provided data and stores all found parameters internally.
|
||||
@@ -133,7 +160,7 @@ class SourceParser(object):
|
||||
re_remove_dots = re.compile(r'\.+$')
|
||||
re_remove_carriage_return = re.compile('\n+')
|
||||
|
||||
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean"])
|
||||
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "increment", "reboot_required", "value", "boolean", "bit"])
|
||||
|
||||
# Order of parameter groups
|
||||
priority = {
|
||||
@@ -164,6 +191,7 @@ class SourceParser(object):
|
||||
long_desc = None
|
||||
tags = {}
|
||||
def_values = {}
|
||||
def_bitmask = {}
|
||||
elif state is not None and state != "comment-processed":
|
||||
m = self.re_comment_end.search(line)
|
||||
if m:
|
||||
@@ -187,6 +215,10 @@ class SourceParser(object):
|
||||
# Take the meta info string and split the code and description
|
||||
metainfo = desc.split(" ", 1)
|
||||
def_values[metainfo[0]] = metainfo[1]
|
||||
elif (tag == "bit"):
|
||||
# Take the meta info string and split the code and description
|
||||
metainfo = desc.split(" ", 1)
|
||||
def_bitmask[metainfo[0]] = metainfo[1]
|
||||
else:
|
||||
tags[tag] = desc
|
||||
current_tag = tag
|
||||
@@ -262,6 +294,8 @@ class SourceParser(object):
|
||||
param.SetField(tag, tags[tag])
|
||||
for def_value in def_values:
|
||||
param.SetEnumValue(def_value, def_values[def_value])
|
||||
for def_bit in def_bitmask:
|
||||
param.SetBitmaskBit(def_bit, def_bitmask[def_bit])
|
||||
# Store the parameter
|
||||
if group not in self.param_groups:
|
||||
self.param_groups[group] = ParameterGroup(group)
|
||||
@@ -284,6 +318,9 @@ class SourceParser(object):
|
||||
for group in self.GetParamGroups():
|
||||
for param in group.GetParams():
|
||||
name = param.GetName()
|
||||
if len(name) > 16:
|
||||
sys.stderr.write("Parameter Name {0} is too long (Limit is 16)\n".format(name))
|
||||
return False
|
||||
board = param.GetFieldValue("board")
|
||||
# Check for duplicates
|
||||
name_plus_board = name + "+" + board
|
||||
@@ -321,6 +358,16 @@ class SourceParser(object):
|
||||
if param.GetEnumValue(code) == "":
|
||||
sys.stderr.write("Description for enum value is empty: {0} {1}\n".format(name, code))
|
||||
return False
|
||||
for index in param.GetBitmaskList():
|
||||
if not self.IsNumber(index):
|
||||
sys.stderr.write("bit value not number: {0} {1}\n".format(name, index))
|
||||
return False
|
||||
if not int(min) <= math.pow(2, int(index)) <= int(max):
|
||||
sys.stderr.write("Bitmask bit must be between {0} and {1}: {2} {3}\n".format(min, max, name, math.pow(2, int(index))))
|
||||
return False
|
||||
if param.GetBitmaskBit(index) == "":
|
||||
sys.stderr.write("Description for bitmask bit is empty: {0} {1}\n".format(name, index))
|
||||
return False
|
||||
return True
|
||||
|
||||
def GetParamGroups(self):
|
||||
|
||||
@@ -33,8 +33,9 @@ class SourceScanner(object):
|
||||
Scans provided file and passes its contents to the parser using
|
||||
parser.Parse method.
|
||||
"""
|
||||
prefix = ".." + os.path.sep + "src" + os.path.sep
|
||||
scope = re.sub(prefix, '', os.path.dirname(os.path.relpath(path)))
|
||||
prefix = "^.*" + os.path.sep + "src" + os.path.sep
|
||||
scope = re.sub(prefix.replace("\\", "/"), "", os.path.dirname(os.path.relpath(path)).replace("\\", "/"))
|
||||
|
||||
with codecs.open(path, 'r', 'utf-8') as f:
|
||||
try:
|
||||
contents = f.read()
|
||||
|
||||
@@ -63,6 +63,14 @@ class XMLOutput():
|
||||
xml_value = ET.SubElement(xml_values, "value")
|
||||
xml_value.attrib["code"] = code;
|
||||
xml_value.text = param.GetEnumValue(code)
|
||||
|
||||
if len(param.GetBitmaskList()) > 0:
|
||||
xml_values = ET.SubElement(xml_param, "bitmask")
|
||||
for index in param.GetBitmaskList():
|
||||
xml_value = ET.SubElement(xml_values, "bit")
|
||||
xml_value.attrib["index"] = index;
|
||||
xml_value.text = param.GetBitmaskBit(index)
|
||||
|
||||
indent(xml_parameters)
|
||||
self.xml_document = ET.ElementTree(xml_parameters)
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python
|
||||
#############################################################################
|
||||
#
|
||||
# Copyright (C) 2013-2015 PX4 Development Team. All rights reserved.
|
||||
# Copyright (C) 2013-2016 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -33,8 +33,8 @@
|
||||
#############################################################################
|
||||
|
||||
"""
|
||||
px_generate_uorb_topic_headers.py
|
||||
Generates c/cpp header files for uorb topics from .msg (ROS syntax)
|
||||
px_generate_uorb_topics.py
|
||||
Generates c/cpp header/source files for uorb topics from .msg (ROS syntax)
|
||||
message files
|
||||
"""
|
||||
from __future__ import print_function
|
||||
@@ -49,6 +49,7 @@ sys.path.append(px4_tools_dir + "/genmsg/src")
|
||||
sys.path.append(px4_tools_dir + "/gencpp/src")
|
||||
|
||||
try:
|
||||
import em
|
||||
import genmsg.template_tools
|
||||
except ImportError as e:
|
||||
print("python import error: ", e)
|
||||
@@ -68,35 +69,99 @@ On Windows please run:
|
||||
''')
|
||||
exit(1)
|
||||
|
||||
__author__ = "Thomas Gubler"
|
||||
__copyright__ = "Copyright (C) 2013-2014 PX4 Development Team."
|
||||
__author__ = "Sergey Belash, Thomas Gubler, Beat Kueng"
|
||||
__copyright__ = "Copyright (C) 2013-2016 PX4 Development Team."
|
||||
__license__ = "BSD"
|
||||
__email__ = "thomasgubler@gmail.com"
|
||||
|
||||
|
||||
msg_template_map = {'msg.h.template': '@NAME@.h'}
|
||||
srv_template_map = {}
|
||||
incl_default = ['std_msgs:./msg/std_msgs']
|
||||
package = 'px4'
|
||||
TEMPLATE_FILE = ['msg.h.template', 'msg.cpp.template']
|
||||
TOPICS_LIST_TEMPLATE_FILE = 'uORBTopics.cpp.template'
|
||||
OUTPUT_FILE_EXT = ['.h', '.cpp']
|
||||
INCL_DEFAULT = ['std_msgs:./msg/std_msgs']
|
||||
PACKAGE = 'px4'
|
||||
TOPICS_TOKEN = '# TOPICS '
|
||||
|
||||
|
||||
def convert_file(filename, outputdir, templatedir, includepath):
|
||||
def get_multi_topics(filename):
|
||||
"""
|
||||
Converts a single .msg file to a uorb header
|
||||
Get TOPICS names from a "# TOPICS" line
|
||||
"""
|
||||
#print("Generating headers from {0}".format(filename))
|
||||
genmsg.template_tools.generate_from_file(filename,
|
||||
package,
|
||||
outputdir,
|
||||
templatedir,
|
||||
includepath,
|
||||
msg_template_map,
|
||||
srv_template_map)
|
||||
ofile = open(filename, 'r')
|
||||
text = ofile.read()
|
||||
result = []
|
||||
for each_line in text.split('\n'):
|
||||
if each_line.startswith (TOPICS_TOKEN):
|
||||
topic_names_str = each_line.strip()
|
||||
topic_names_str = topic_names_str.replace(TOPICS_TOKEN, "")
|
||||
result.extend(topic_names_str.split(" "))
|
||||
ofile.close()
|
||||
return result
|
||||
|
||||
def get_msgs_list(msgdir):
|
||||
"""
|
||||
Makes list of msg files in the given directory
|
||||
"""
|
||||
return [fn for fn in os.listdir(msgdir) if fn.endswith(".msg")]
|
||||
|
||||
|
||||
def convert_dir(inputdir, outputdir, templatedir):
|
||||
def generate_output_from_file(format_idx, filename, outputdir, templatedir, includepath):
|
||||
"""
|
||||
Converts all .msg files in inputdir to uORB header files
|
||||
Converts a single .msg file to an uorb header/source file
|
||||
"""
|
||||
msg_context = genmsg.msg_loader.MsgContext.create_default()
|
||||
full_type_name = genmsg.gentools.compute_full_type_name(PACKAGE, os.path.basename(filename))
|
||||
spec = genmsg.msg_loader.load_msg_from_file(msg_context, filename, full_type_name)
|
||||
topics = get_multi_topics(filename)
|
||||
if includepath:
|
||||
search_path = genmsg.command_line.includepath_to_dict(includepath)
|
||||
else:
|
||||
search_path = {}
|
||||
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
|
||||
md5sum = genmsg.gentools.compute_md5(msg_context, spec)
|
||||
if len(topics) == 0:
|
||||
topics.append(spec.short_name)
|
||||
em_globals = {
|
||||
"file_name_in": filename,
|
||||
"md5sum": md5sum,
|
||||
"search_path": search_path,
|
||||
"msg_context": msg_context,
|
||||
"spec": spec,
|
||||
"topics": topics
|
||||
}
|
||||
|
||||
# Make sure output directory exists:
|
||||
if not os.path.isdir(outputdir):
|
||||
os.makedirs(outputdir)
|
||||
|
||||
template_file = os.path.join(templatedir, TEMPLATE_FILE[format_idx])
|
||||
output_file = os.path.join(outputdir, spec.short_name +
|
||||
OUTPUT_FILE_EXT[format_idx])
|
||||
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
|
||||
def generate_by_template(output_file, template_file, em_globals):
|
||||
"""
|
||||
Invokes empy intepreter to geneate output_file by the
|
||||
given template_file and predefined em_globals dict
|
||||
"""
|
||||
ofile = open(output_file, 'w')
|
||||
# todo, reuse interpreter
|
||||
interpreter = em.Interpreter(output=ofile, globals=em_globals, options={em.RAW_OPT:True,em.BUFFERED_OPT:True})
|
||||
if not os.path.isfile(template_file):
|
||||
ofile.close()
|
||||
os.remove(output_file)
|
||||
raise RuntimeError("Template file %s not found" % (template_file))
|
||||
interpreter.file(open(template_file)) #todo try
|
||||
interpreter.shutdown()
|
||||
ofile.close()
|
||||
return True
|
||||
|
||||
|
||||
def convert_dir(format_idx, inputdir, outputdir, templatedir):
|
||||
"""
|
||||
Converts all .msg files in inputdir to uORB header/source files
|
||||
"""
|
||||
|
||||
# Find the most recent modification time in input dir
|
||||
@@ -122,7 +187,7 @@ def convert_dir(inputdir, outputdir, templatedir):
|
||||
if (maxinputtime != 0 and maxouttime != 0 and maxinputtime < maxouttime):
|
||||
return False
|
||||
|
||||
includepath = incl_default + [':'.join([package, inputdir])]
|
||||
includepath = INCL_DEFAULT + [':'.join([PACKAGE, inputdir])]
|
||||
for f in os.listdir(inputdir):
|
||||
# Ignore hidden files
|
||||
if f.startswith("."):
|
||||
@@ -133,11 +198,10 @@ def convert_dir(inputdir, outputdir, templatedir):
|
||||
if not os.path.isfile(fn):
|
||||
continue
|
||||
|
||||
convert_file(fn,
|
||||
outputdir,
|
||||
templatedir,
|
||||
includepath)
|
||||
if fn[-4:].lower() != '.msg':
|
||||
continue
|
||||
|
||||
generate_output_from_file(format_idx, fn, outputdir, templatedir, includepath)
|
||||
return True
|
||||
|
||||
|
||||
@@ -151,15 +215,15 @@ def copy_changed(inputdir, outputdir, prefix='', quiet=False):
|
||||
if not os.path.isdir(outputdir):
|
||||
os.makedirs(outputdir)
|
||||
|
||||
for f in os.listdir(inputdir):
|
||||
fni = os.path.join(inputdir, f)
|
||||
for input_file in os.listdir(inputdir):
|
||||
fni = os.path.join(inputdir, input_file)
|
||||
if os.path.isfile(fni):
|
||||
# Check if f exists in outpoutdir, copy the file if not
|
||||
fno = os.path.join(outputdir, prefix + f)
|
||||
# Check if input_file exists in outpoutdir, copy the file if not
|
||||
fno = os.path.join(outputdir, prefix + input_file)
|
||||
if not os.path.isfile(fno):
|
||||
shutil.copy(fni, fno)
|
||||
if not quiet:
|
||||
print("{0}: new header file".format(f))
|
||||
print("{0}: new header file".format(fno))
|
||||
continue
|
||||
|
||||
if os.path.getmtime(fni) > os.path.getmtime(fno):
|
||||
@@ -168,26 +232,39 @@ def copy_changed(inputdir, outputdir, prefix='', quiet=False):
|
||||
if not filecmp.cmp(fni, fno):
|
||||
shutil.copy(fni, fno)
|
||||
if not quiet:
|
||||
print("{0}: updated".format(f))
|
||||
print("{0}: updated".format(input_file))
|
||||
continue
|
||||
|
||||
if not quiet:
|
||||
print("{0}: unchanged".format(f))
|
||||
print("{0}: unchanged".format(input_file))
|
||||
|
||||
|
||||
def convert_dir_save(inputdir, outputdir, templatedir, temporarydir, prefix, quiet=False):
|
||||
def convert_dir_save(format_idx, inputdir, outputdir, templatedir, temporarydir, prefix, quiet=False):
|
||||
"""
|
||||
Converts all .msg files in inputdir to uORB header files
|
||||
Unchanged existing files are not overwritten.
|
||||
"""
|
||||
# Create new headers in temporary output directory
|
||||
convert_dir(inputdir, temporarydir, templatedir)
|
||||
convert_dir(format_idx, inputdir, temporarydir, templatedir)
|
||||
if generate_idx == 1:
|
||||
generate_topics_list_file(inputdir, temporarydir, templatedir)
|
||||
# Copy changed headers from temporary dir to output dir
|
||||
copy_changed(temporarydir, outputdir, prefix, quiet)
|
||||
|
||||
def generate_topics_list_file(msgdir, outputdir, templatedir):
|
||||
# generate cpp file with topics list
|
||||
tl_globals = {"msgs" : get_msgs_list(msgdir)}
|
||||
tl_template_file = os.path.join(templatedir, TOPICS_LIST_TEMPLATE_FILE)
|
||||
tl_out_file = os.path.join(outputdir, TOPICS_LIST_TEMPLATE_FILE.replace(".template", ""))
|
||||
generate_by_template(tl_out_file, tl_template_file, tl_globals)
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Convert msg files to uorb headers')
|
||||
description='Convert msg files to uorb headers/sources')
|
||||
parser.add_argument('--headers', help='Generate header files',
|
||||
action='store_true')
|
||||
parser.add_argument('--sources', help='Generate source files',
|
||||
action='store_true')
|
||||
parser.add_argument('-d', dest='dir', help='directory with msg files')
|
||||
parser.add_argument('-f', dest='file',
|
||||
help="files to convert (use only without -d)",
|
||||
@@ -206,15 +283,22 @@ if __name__ == "__main__":
|
||||
' name when converting directories')
|
||||
args = parser.parse_args()
|
||||
|
||||
if args.headers:
|
||||
generate_idx = 0
|
||||
elif args.sources:
|
||||
generate_idx = 1
|
||||
else:
|
||||
print('Error: either --headers or --sources must be specified')
|
||||
exit(-1)
|
||||
|
||||
if args.file is not None:
|
||||
for f in args.file:
|
||||
convert_file(
|
||||
f,
|
||||
args.outputdir,
|
||||
args.templatedir,
|
||||
incl_default)
|
||||
for f in args.file:
|
||||
generate_output_from_file(generate_idx, f, args.outputdir, args.templatedir, INCL_DEFAULT)
|
||||
if generate_idx == 1:
|
||||
generate_topics_list_file(args.dir, args.outputdir, args.templatedir)
|
||||
elif args.dir is not None:
|
||||
convert_dir_save(
|
||||
convert_dir_save(
|
||||
generate_idx,
|
||||
args.dir,
|
||||
args.outputdir,
|
||||
args.templatedir,
|
||||
@@ -0,0 +1,171 @@
|
||||
|
||||
# helper methods & common code for the uorb message templates msg.{cpp,h}.template
|
||||
|
||||
# Another positive effect of having the code here, is that this file will get
|
||||
# precompiled and thus message generation will be much faster
|
||||
|
||||
|
||||
import genmsg.msgs
|
||||
import gencpp
|
||||
|
||||
type_map = {
|
||||
'int8': 'int8_t',
|
||||
'int16': 'int16_t',
|
||||
'int32': 'int32_t',
|
||||
'int64': 'int64_t',
|
||||
'uint8': 'uint8_t',
|
||||
'uint16': 'uint16_t',
|
||||
'uint32': 'uint32_t',
|
||||
'uint64': 'uint64_t',
|
||||
'float32': 'float',
|
||||
'float64': 'double',
|
||||
'bool': 'bool',
|
||||
'char': 'char',
|
||||
}
|
||||
|
||||
msgtype_size_map = {
|
||||
'int8': 1,
|
||||
'int16': 2,
|
||||
'int32': 4,
|
||||
'int64': 8,
|
||||
'uint8': 1,
|
||||
'uint16': 2,
|
||||
'uint32': 4,
|
||||
'uint64': 8,
|
||||
'float32': 4,
|
||||
'float64': 8,
|
||||
'bool': 1,
|
||||
'char': 1,
|
||||
}
|
||||
|
||||
|
||||
def bare_name(msg_type):
|
||||
"""
|
||||
Get bare_name from <dir>/<bare_name>[x] format
|
||||
"""
|
||||
bare = msg_type
|
||||
if '/' in msg_type:
|
||||
# removing prefix
|
||||
bare = (msg_type.split('/'))[1]
|
||||
# removing suffix
|
||||
return bare.split('[')[0]
|
||||
|
||||
|
||||
def sizeof_field_type(field):
|
||||
"""
|
||||
Get size of a field, used for sorting
|
||||
"""
|
||||
bare_name_str = bare_name(field.type)
|
||||
if bare_name_str in msgtype_size_map:
|
||||
return msgtype_size_map[bare_name_str]
|
||||
return 0 # this is for non-builtin types: sort them at the end
|
||||
|
||||
def get_children_fields(base_type, search_path):
|
||||
(package, name) = genmsg.names.package_resource_name(base_type)
|
||||
tmp_msg_context = genmsg.msg_loader.MsgContext.create_default()
|
||||
spec_temp = genmsg.msg_loader.load_msg_by_type(tmp_msg_context, '%s/%s' %(package, name), search_path)
|
||||
sorted_fields = sorted(spec_temp.parsed_fields(), key=sizeof_field_type, reverse=True)
|
||||
return sorted_fields
|
||||
|
||||
def add_padding_bytes(fields, search_path):
|
||||
"""
|
||||
Add padding fields before the embedded types, at the end and calculate the
|
||||
struct size
|
||||
returns a tuple with the struct size and padding at the end
|
||||
"""
|
||||
struct_size = 8 # account for the timestamp
|
||||
align_to = 8 # this is always 8, because of the 64bit timestamp
|
||||
i = 0
|
||||
padding_idx = 0
|
||||
while i < len(fields):
|
||||
field = fields[i]
|
||||
if not field.is_header:
|
||||
a_pos = field.type.find('[')
|
||||
array_size = 1
|
||||
if field.is_array:
|
||||
array_size = field.array_len
|
||||
if field.is_builtin:
|
||||
field.sizeof_field_type = sizeof_field_type(field)
|
||||
else:
|
||||
# embedded type: may need to add padding
|
||||
num_padding_bytes = align_to - (struct_size % align_to)
|
||||
if num_padding_bytes != align_to:
|
||||
padding_field = genmsg.Field('_padding'+str(padding_idx),
|
||||
'uint8['+str(num_padding_bytes)+']')
|
||||
padding_idx += 1
|
||||
padding_field.sizeof_field_type = 1
|
||||
struct_size += num_padding_bytes
|
||||
fields.insert(i, padding_field)
|
||||
i += 1
|
||||
children_fields = get_children_fields(field.base_type, search_path)
|
||||
field.sizeof_field_type, unused = add_padding_bytes(children_fields,
|
||||
search_path)
|
||||
struct_size += field.sizeof_field_type * array_size
|
||||
i += 1
|
||||
|
||||
# add padding at the end (necessary for embedded types)
|
||||
num_padding_bytes = align_to - (struct_size % align_to)
|
||||
if num_padding_bytes == align_to:
|
||||
num_padding_bytes = 0
|
||||
else:
|
||||
padding_field = genmsg.Field('_padding'+str(padding_idx),
|
||||
'uint8['+str(num_padding_bytes)+']')
|
||||
padding_idx += 1
|
||||
padding_field.sizeof_field_type = 1
|
||||
struct_size += num_padding_bytes
|
||||
fields.append(padding_field)
|
||||
return (struct_size, num_padding_bytes)
|
||||
|
||||
|
||||
def convert_type(spec_type):
|
||||
"""
|
||||
Convert from msg type to C type
|
||||
"""
|
||||
bare_type = spec_type
|
||||
if '/' in spec_type:
|
||||
# removing prefix
|
||||
bare_type = (spec_type.split('/'))[1]
|
||||
|
||||
msg_type, is_array, array_length = genmsg.msgs.parse_type(bare_type)
|
||||
c_type = msg_type
|
||||
if msg_type in type_map:
|
||||
c_type = type_map[msg_type]
|
||||
if is_array:
|
||||
return c_type + "[" + str(array_length) + "]"
|
||||
return c_type
|
||||
|
||||
|
||||
def print_field_def(field):
|
||||
"""
|
||||
Print the C type from a field
|
||||
"""
|
||||
type_name = field.type
|
||||
# detect embedded types
|
||||
sl_pos = type_name.find('/')
|
||||
type_appendix = ''
|
||||
type_prefix = ''
|
||||
if (sl_pos >= 0):
|
||||
type_name = type_name[sl_pos + 1:]
|
||||
type_prefix = 'struct '
|
||||
type_appendix = '_s'
|
||||
|
||||
# detect arrays
|
||||
a_pos = type_name.find('[')
|
||||
array_size = ''
|
||||
if (a_pos >= 0):
|
||||
# field is array
|
||||
array_size = type_name[a_pos:]
|
||||
type_name = type_name[:a_pos]
|
||||
|
||||
if type_name in type_map:
|
||||
# need to add _t: int8 --> int8_t
|
||||
type_px4 = type_map[type_name]
|
||||
else:
|
||||
type_px4 = type_name
|
||||
|
||||
comment = ''
|
||||
if field.name.startswith('_padding'):
|
||||
comment = ' // required for logger'
|
||||
|
||||
print('\t%s%s%s %s%s;%s'%(type_prefix, type_px4, type_appendix, field.name,
|
||||
array_size, comment))
|
||||
@@ -71,7 +71,7 @@ def main():
|
||||
const="",
|
||||
metavar="BOARD",
|
||||
help="Board to create airframes xml for")
|
||||
parser.add_argument("-v", "--verbose", help="verbose output")
|
||||
parser.add_argument('-v', '--verbose', action='store_true', help="verbose output")
|
||||
args = parser.parse_args()
|
||||
|
||||
# Check for valid command
|
||||
|
||||
@@ -107,7 +107,7 @@ def main():
|
||||
metavar="SUMMARY",
|
||||
default="Automagically updated parameter documentation from code.",
|
||||
help="DokuWiki page edit summary")
|
||||
parser.add_argument("-v", "--verbose", help="verbose output")
|
||||
parser.add_argument('-v', '--verbose', action='store_true', help="verbose output")
|
||||
args = parser.parse_args()
|
||||
|
||||
# Check for valid command
|
||||
|
||||
+23
-11
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2014-2015 PX4 Development Team. All rights reserved.
|
||||
# Copyright (C) 2014-2016 PX4 Development Team. All rights reserved.
|
||||
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -35,7 +35,12 @@
|
||||
|
||||
"""
|
||||
px_romfs_pruner.py:
|
||||
Delete all comments and newlines before ROMFS is converted to an image
|
||||
Try to keep size of ROMFS minimal.
|
||||
|
||||
This script goes through the temporarily copied ROMFS data and deletes all
|
||||
comments, empty lines and leading whitespace.
|
||||
It also deletes hidden files such as auto-saved backups that a text editor
|
||||
might have left in the tree.
|
||||
|
||||
@author: Julian Oes <julian@oes.ch>
|
||||
"""
|
||||
@@ -53,18 +58,25 @@ def main():
|
||||
help="ROMFS scratch folder.")
|
||||
args = parser.parse_args()
|
||||
|
||||
#print("Pruning ROMFS files.")
|
||||
|
||||
# go through
|
||||
# go through temp folder
|
||||
for (root, dirs, files) in os.walk(args.folder):
|
||||
for file in files:
|
||||
# only prune text files
|
||||
if ".zip" in file or ".bin" in file or ".swp" in file \
|
||||
or ".data" in file or ".DS_Store" in file \
|
||||
or file.startswith("."):
|
||||
file_path = os.path.join(root, file)
|
||||
|
||||
# delete hidden files
|
||||
if file.startswith("."):
|
||||
os.remove(file_path)
|
||||
continue
|
||||
|
||||
file_path = os.path.join(root, file)
|
||||
# delete documentation
|
||||
if file.startswith("README"):
|
||||
os.remove(file_path)
|
||||
continue
|
||||
|
||||
# only prune text files
|
||||
if ".zip" in file or ".bin" in file or ".swp" in file \
|
||||
or ".data" in file or ".DS_Store" in file:
|
||||
continue
|
||||
|
||||
# read file line by line
|
||||
pruned_content = ""
|
||||
@@ -77,7 +89,7 @@ def main():
|
||||
else:
|
||||
if not line.isspace() \
|
||||
and not line.strip().startswith("#"):
|
||||
pruned_content += line
|
||||
pruned_content += line.strip() + "\n"
|
||||
# overwrite old scratch file
|
||||
with open(file_path, "wb") as f:
|
||||
pruned_content = re.sub("\r\n", "\n", pruned_content)
|
||||
|
||||
Executable
+32
@@ -0,0 +1,32 @@
|
||||
#!/bin/bash
|
||||
|
||||
if [[ "$#" < 2 ]]; then
|
||||
echo "usage: scp_upload.sh SRC1 [SRC2 ...] DEST"
|
||||
exit
|
||||
fi
|
||||
|
||||
if [ -z ${AUTOPILOT_HOST+x} ]; then
|
||||
host=px4autopilot
|
||||
echo "\$AUTOPILOT_HOST is not set (use default: $host)"
|
||||
else
|
||||
host=$AUTOPILOT_HOST
|
||||
echo "\$AUTOPILOT_HOST is set to $host"
|
||||
fi
|
||||
|
||||
echo "Uploading..."
|
||||
|
||||
# Get last argument
|
||||
for last; do true; done
|
||||
|
||||
# Go through source files and push them one by one.
|
||||
i=0
|
||||
for arg
|
||||
do
|
||||
if [[ $((i+1)) == "$#" ]]; then
|
||||
break
|
||||
fi
|
||||
# echo "Pushing $arg to $last"
|
||||
#adb push $arg $last
|
||||
scp $arg pi@$host:$last
|
||||
((i+=1))
|
||||
done
|
||||
+10
-2
@@ -8,6 +8,14 @@ logconv.m: This is a MATLAB script which will automatically convert and display
|
||||
|
||||
sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run:
|
||||
|
||||
python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n ""
|
||||
python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n ""
|
||||
|
||||
Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux.
|
||||
geo_tag_images.py: Use this script to geotag a set of images. It uses GPS time and file creation date to synchronize the images, so it needs that the images have a valid creation date.
|
||||
|
||||
python geo_tag_images.py --logfile=mylog.bin --input=images/ --output=tagged/
|
||||
|
||||
geotagging.py: Use this script to geotag a set of images. It uses the CAM trigger data from the log file for image association.
|
||||
|
||||
python geotagging.py --logfile=mylog.bin --input=images/ --output=tagged/
|
||||
|
||||
Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux.
|
||||
|
||||
@@ -0,0 +1,375 @@
|
||||
#!/usr/bin/env python
|
||||
#
|
||||
# Tag the images recorded during a flight with geo location extracted from
|
||||
# a PX4 binary log file.
|
||||
#
|
||||
# This file accepts *.jpg format images and reads position information
|
||||
# from a *.bin file
|
||||
#
|
||||
# Example Syntax:
|
||||
# python geotag.py --logfile=log001.bin --input=images/ --output=imagesWithTag/ --offset=-0.4 -v
|
||||
#
|
||||
# Author: Hector Azpurua
|
||||
# Based on the script of Andreas Bircher
|
||||
|
||||
import os
|
||||
import re
|
||||
import sys
|
||||
import csv
|
||||
import bisect
|
||||
import pyexiv2
|
||||
import argparse
|
||||
from lxml import etree
|
||||
import datetime, calendar
|
||||
from shutil import copyfile
|
||||
from pykml.factory import KML_ElementMaker as KML
|
||||
from pykml.factory import GX_ElementMaker as GX
|
||||
|
||||
|
||||
class GpsPosition(object):
|
||||
def __init__(self, timestamp, lat, lon, alt):
|
||||
self.timestamp = timestamp
|
||||
self.lat = float(lat)
|
||||
self.lon = float(lon)
|
||||
self.alt = float(alt)
|
||||
|
||||
|
||||
class Main:
|
||||
def __init__(self):
|
||||
"""
|
||||
|
||||
:param logfile:
|
||||
:param input:
|
||||
:param output:
|
||||
:param offset:
|
||||
:param verbose:
|
||||
:return:
|
||||
"""
|
||||
args = self.get_arg()
|
||||
|
||||
self.logfile = args['logfile']
|
||||
self.input = args['input']
|
||||
self.output = args['output']
|
||||
self.klm = args['klm']
|
||||
self.verbose = args['verbose']
|
||||
self.offset = args['offset']
|
||||
self.time_tresh = args['treshold']
|
||||
|
||||
self.tdiff_list = []
|
||||
self.non_processed_files = []
|
||||
self.tagged_gps = []
|
||||
self.gps_list = self.load_gps_from_log(self.logfile, self.offset)
|
||||
self.img_list = self.load_image_list(self.input)
|
||||
|
||||
if len(self.img_list) <= 0:
|
||||
print '[ERROR] Cannot load JPG images from input folder, please check filename extensions.'
|
||||
sys.exit(1)
|
||||
|
||||
if not os.path.exists(self.output):
|
||||
os.makedirs(self.output)
|
||||
|
||||
if not self.output.endswith(os.path.sep):
|
||||
self.output += os.path.sep
|
||||
|
||||
self.tag_images()
|
||||
|
||||
if self.klm and len(self.tdiff_list) > 0:
|
||||
self.gen_klm()
|
||||
|
||||
if len(self.non_processed_files) > 0:
|
||||
print '[WARNING] Some images werent processed:'
|
||||
for elem in self.non_processed_files:
|
||||
print '\t', elem
|
||||
|
||||
@staticmethod
|
||||
def to_degree(value, loc):
|
||||
"""
|
||||
Convert a lat or lon value to degrees/minutes/seconds
|
||||
:param value: the latitude or longitude value
|
||||
:param loc: could be ["S", "N"] or ["W", "E"]
|
||||
:return:
|
||||
"""
|
||||
if value < 0:
|
||||
loc_value = loc[0]
|
||||
elif value > 0:
|
||||
loc_value = loc[1]
|
||||
else:
|
||||
loc_value = ""
|
||||
|
||||
absolute_value = abs(value)
|
||||
deg = int(absolute_value)
|
||||
t1 = (absolute_value-deg) * 60
|
||||
minute = int(t1)
|
||||
sec = round((t1 - minute) * 60, 5)
|
||||
|
||||
return deg, minute, sec, loc_value
|
||||
|
||||
@staticmethod
|
||||
def gps_week_seconds_to_datetime(gpsweek, gpsmillis, leapmillis=0):
|
||||
"""
|
||||
Convert GPS week and seconds to datetime object, using leap milliseconds if necessary
|
||||
:param gpsweek:
|
||||
:param gpsmillis:
|
||||
:param leapmillis:
|
||||
:return:
|
||||
"""
|
||||
datetimeformat = "%Y-%m-%d %H:%M:%S.%f"
|
||||
epoch = datetime.datetime.strptime("1980-01-06 00:00:00.000", datetimeformat)
|
||||
elapsed = datetime.timedelta(days=(gpsweek * 7), milliseconds=(gpsmillis + leapmillis))
|
||||
|
||||
return Main.utc_to_local(epoch + elapsed)
|
||||
|
||||
@staticmethod
|
||||
def utc_to_local(utc_dt):
|
||||
"""
|
||||
Convert UTC time in local time
|
||||
:param utc_dt:
|
||||
:return:
|
||||
"""
|
||||
timestamp = calendar.timegm(utc_dt.timetuple()) # use integer timestamp to avoid precision lost
|
||||
local_dt = datetime.datetime.fromtimestamp(timestamp)
|
||||
assert utc_dt.resolution >= datetime.timedelta(microseconds=1)
|
||||
|
||||
return local_dt.replace(microsecond=utc_dt.microsecond)
|
||||
|
||||
def gen_klm(self):
|
||||
"""
|
||||
Generate a KML file with keypoints on the locations of the pictures, including height
|
||||
:return:
|
||||
"""
|
||||
style_dot = "sn_shaded_dot"
|
||||
style_path = "red_path"
|
||||
|
||||
doc = KML.kml(
|
||||
KML.Document(
|
||||
KML.Name("GPS of the images"),
|
||||
KML.Style(
|
||||
KML.IconStyle(
|
||||
KML.scale(0.4),
|
||||
KML.Icon(
|
||||
KML.href("http://maps.google.com/mapfiles/kml/shapes/shaded_dot.png")
|
||||
),
|
||||
),
|
||||
id=style_dot,
|
||||
),
|
||||
KML.Style(
|
||||
KML.LineStyle(
|
||||
KML.color('7f0000ff'),
|
||||
KML.width(6),
|
||||
GX.labelVisibility('1'),
|
||||
),
|
||||
id=style_path
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
# create points
|
||||
for i, gps in enumerate(self.tagged_gps):
|
||||
ii = i + 1
|
||||
doc.Document.append(
|
||||
KML.Placemark(
|
||||
KML.styleUrl('#{0}'.format(style_dot)),
|
||||
KML.Point(
|
||||
KML.extrude(True),
|
||||
KML.altitudeMode('relativeToGround'),
|
||||
KML.coordinates("{},{},{}".format(gps.lon, gps.lat, gps.alt))
|
||||
),
|
||||
KML.name(str(ii)) if ii % 5 == 0 or ii == 1 else KML.name()
|
||||
)
|
||||
)
|
||||
|
||||
# create the path
|
||||
doc.Document.append(
|
||||
KML.Placemark(
|
||||
KML.styleUrl('#{0}'.format(style_path)),
|
||||
KML.LineString(
|
||||
KML.altitudeMode('relativeToGround'),
|
||||
KML.coordinates(
|
||||
' '.join(["{},{},{}".format(gps.lon, gps.lat, gps.alt) for gps in self.tagged_gps])
|
||||
)
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
s = etree.tostring(doc)
|
||||
|
||||
file_path = self.output + 'GoogleEarth_points.kml'
|
||||
f = open(file_path,'w')
|
||||
f.write(s)
|
||||
f.close()
|
||||
|
||||
print '[INFO] KML file generated on:', file_path
|
||||
|
||||
def get_closest_datetime_index(self, datetime_list, elem):
|
||||
"""
|
||||
Get the closest element between a list of datetime objects and a date
|
||||
:param datetime_list:
|
||||
:param elem:
|
||||
:return:
|
||||
"""
|
||||
i = bisect.bisect_left(datetime_list, elem)
|
||||
date = datetime_list[i]
|
||||
diff = (date - elem).total_seconds()
|
||||
|
||||
if diff > self.time_tresh:
|
||||
return -1, diff
|
||||
|
||||
return i, diff
|
||||
|
||||
def set_gps_location(self, file_name, lat, lng, alt):
|
||||
"""
|
||||
Add the GPS tag and altitude to a image file
|
||||
:param file_name:
|
||||
:param lat:
|
||||
:param lng:
|
||||
:param alt:
|
||||
:return:
|
||||
"""
|
||||
lat_deg = self.to_degree(lat, ["S", "N"])
|
||||
lng_deg = self.to_degree(lng, ["W", "E"])
|
||||
|
||||
exiv_lat = (pyexiv2.Rational(lat_deg[0] * 60 + lat_deg[1], 60),
|
||||
pyexiv2.Rational(lat_deg[2] * 100, 6000), pyexiv2.Rational(0, 1))
|
||||
exiv_lng = (pyexiv2.Rational(lng_deg[0] * 60 + lng_deg[1], 60),
|
||||
pyexiv2.Rational(lng_deg[2] * 100, 6000), pyexiv2.Rational(0, 1))
|
||||
|
||||
try:
|
||||
exiv_image = pyexiv2.ImageMetadata(file_name)
|
||||
exiv_image.read()
|
||||
|
||||
exiv_image["Exif.GPSInfo.GPSLatitude"] = exiv_lat
|
||||
exiv_image["Exif.GPSInfo.GPSLatitudeRef"] = lat_deg[3]
|
||||
exiv_image["Exif.GPSInfo.GPSLongitude"] = exiv_lng
|
||||
exiv_image["Exif.GPSInfo.GPSLongitudeRef"] = lng_deg[3]
|
||||
exiv_image["Exif.GPSInfo.GPSAltitude"] = pyexiv2.Rational(alt, 1)
|
||||
exiv_image["Exif.GPSInfo.GPSAltitudeRef"] = '0'
|
||||
exiv_image["Exif.Image.GPSTag"] = 654
|
||||
exiv_image["Exif.GPSInfo.GPSMapDatum"] = "WGS-84"
|
||||
exiv_image["Exif.GPSInfo.GPSVersionID"] = '2 0 0 0'
|
||||
|
||||
exiv_image.write(True)
|
||||
except Exception as e:
|
||||
print '[ERROR]', e
|
||||
|
||||
def load_gps_from_log(self, log_file, offset):
|
||||
"""
|
||||
Load gps list from PX4 binary log
|
||||
:param log_file:
|
||||
:param offset:
|
||||
:return:
|
||||
"""
|
||||
os.system('python sdlog2_dump.py ' + log_file + ' -f log.csv')
|
||||
f = open('log.csv', 'rb')
|
||||
reader = csv.reader(f)
|
||||
headers = reader.next()
|
||||
line = {}
|
||||
for h in headers:
|
||||
line[h] = []
|
||||
|
||||
for row in reader:
|
||||
for h, v in zip(headers, row):
|
||||
line[h].append(v)
|
||||
|
||||
gps_list = []
|
||||
for seq in range(0, len(line['GPS_Lat']) - 1):
|
||||
gps_time = int(line['GPS_TimeMS'][seq + 1])
|
||||
gps_week = int(line['GPS_Week'][seq + 1])
|
||||
gps_lat = float(line['GPS_Lat'][seq + 1])
|
||||
gps_lon = float(line['GPS_Lng'][seq + 1])
|
||||
gps_alt = float(line['GPS_RelAlt'][seq + 1])
|
||||
|
||||
date = self.gps_week_seconds_to_datetime(gps_week, gps_time, leapmillis=offset)
|
||||
print date
|
||||
gps_list.append(GpsPosition(date, gps_lat, gps_lon, gps_alt))
|
||||
|
||||
return gps_list
|
||||
|
||||
def load_image_list(self, input_folder, file_type='jpg'):
|
||||
"""
|
||||
Load image list from a folder given a file type
|
||||
:param input_folder:
|
||||
:param file_type:
|
||||
:return:
|
||||
"""
|
||||
self.img_list = [input_folder + filename for filename in os.listdir(input_folder)
|
||||
if re.search(r'\.'+file_type+'$', filename, re.IGNORECASE)]
|
||||
self.img_list = sorted(self.img_list)
|
||||
return self.img_list
|
||||
|
||||
def tag_images(self):
|
||||
"""
|
||||
Tag the image list using the GPS loaded from the LOG file
|
||||
:return:
|
||||
"""
|
||||
tagged_gps = []
|
||||
img_size = len(self.img_list)
|
||||
print '[INFO] Number of images:', img_size
|
||||
|
||||
dt_list = [x.timestamp for x in self.gps_list]
|
||||
|
||||
img_seq = 1
|
||||
|
||||
for i in xrange(img_size):
|
||||
base_path, filename = os.path.split(self.img_list[i])
|
||||
cdate = datetime.datetime.fromtimestamp(os.path.getmtime(self.img_list[i]))
|
||||
gps_i, img_tdiff = self.get_closest_datetime_index(dt_list, cdate)
|
||||
|
||||
if gps_i == -1:
|
||||
self.non_processed_files.append(filename)
|
||||
continue
|
||||
|
||||
closest_gps = self.gps_list[gps_i]
|
||||
self.tdiff_list.append(img_tdiff)
|
||||
|
||||
if self.verbose:
|
||||
msg = "[DEBUG] %s/%s) %s\n\timg %s -> gps %s (%ss)\n\tlat:%s, lon:%s, alt:%s".ljust(60) %\
|
||||
(i+1, img_size, filename, cdate, closest_gps.timestamp, img_tdiff, closest_gps.lat, closest_gps.lon, closest_gps.alt)
|
||||
print msg
|
||||
|
||||
copyfile(self.img_list[i], self.output + str(img_seq) + filename)
|
||||
self.set_gps_location(self.output + str(img_seq) + filename, closest_gps.lat, closest_gps.lon, closest_gps.alt)
|
||||
self.tagged_gps.append(closest_gps)
|
||||
img_seq += 1
|
||||
|
||||
if len(self.tdiff_list) > 0:
|
||||
print '[INFO] Mean diff in seconds:', sum(self.tdiff_list) / float(len(self.tdiff_list))
|
||||
|
||||
@staticmethod
|
||||
def get_arg():
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Geotag script to add GPS info to pictures from PX4 binary log files.'\
|
||||
'It uses synchronized time to allocate GPS positions.'
|
||||
)
|
||||
|
||||
parser.add_argument(
|
||||
'-l', '--logfile', help='PX4 log file containing recorded positions.', required=True
|
||||
)
|
||||
parser.add_argument(
|
||||
'-i', '--input', help='Input folder containing untagged images.', required=True
|
||||
)
|
||||
parser.add_argument(
|
||||
'-o', '--output', help='Output folder to contain tagged images.', required=True
|
||||
)
|
||||
parser.add_argument(
|
||||
'-t', '--treshold', help='Time treshold between the GPS time and the local image time.',
|
||||
default=1, required=False, type=float
|
||||
)
|
||||
parser.add_argument(
|
||||
'-of', '--offset', help='Time offset in MILLISECONDS between the GPS time and the local time.',
|
||||
default=-17000, required=False, type=float
|
||||
)
|
||||
parser.add_argument(
|
||||
'-klm', '--klm', help='Save the in KML format the information of all tagged images.',
|
||||
required=False, action='store_true'
|
||||
)
|
||||
parser.add_argument(
|
||||
'-v', '--verbose', help='Prints lots of information.',
|
||||
required=False, action='store_true'
|
||||
)
|
||||
|
||||
args = vars(parser.parse_args())
|
||||
return args
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
m = Main()
|
||||
+1
-1
Submodule Tools/sitl_gazebo updated: 9353834b2f...00dcabb1c2
Executable
+52
@@ -0,0 +1,52 @@
|
||||
#!/bin/bash
|
||||
|
||||
sitl_num=2
|
||||
|
||||
sim_port=15019
|
||||
mav_port=15010
|
||||
mav_port2=15011
|
||||
|
||||
mav_oport=15015
|
||||
mav_oport2=15016
|
||||
|
||||
port_step=10
|
||||
|
||||
src_path=`pwd`
|
||||
|
||||
rc_script="posix-configs/SITL/init/rcS_multiple"
|
||||
build_path=${src_path}/build_posix_sitl_default
|
||||
|
||||
pkill px4
|
||||
sleep 2
|
||||
|
||||
cd $build_path/src/firmware/posix
|
||||
|
||||
user=`whoami`
|
||||
n=1
|
||||
while [ $n -le $sitl_num ]; do
|
||||
if [ ! -d $n ]; then
|
||||
mkdir -p $n
|
||||
cd $n
|
||||
|
||||
mkdir -p rootfs/fs/microsd
|
||||
mkdir -p rootfs/eeprom
|
||||
touch rootfs/eeprom/parameters
|
||||
|
||||
cp ${src_path}/ROMFS/px4fmu_common/mixers/quad_w.main.mix ./
|
||||
cat ${src_path}/${rc_script}_gazebo_iris | sed s/_SIMPORT_/${sim_port}/ | sed s/_MAVPORT_/${mav_port}/g | sed s/_MAVOPORT_/${mav_oport}/ | sed s/_MAVPORT2_/${mav_port2}/ | sed s/_MAVOPORT2_/${mav_oport2}/ > rcS
|
||||
cd ../
|
||||
fi
|
||||
|
||||
cd $n
|
||||
|
||||
sudo -b -u $user ../px4 -d rcS >out.log 2>err.log
|
||||
|
||||
cd ../
|
||||
|
||||
n=$(($n + 1))
|
||||
sim_port=$(($sim_port + $port_step))
|
||||
mav_port=$(($mav_port + $port_step))
|
||||
mav_port2=$(($mav_port2 + $port_step))
|
||||
mav_oport=$(($mav_oport + $port_step))
|
||||
mav_oport2=$(($mav_oport2 + $port_step))
|
||||
done
|
||||
+23
-19
@@ -43,7 +43,7 @@ fi
|
||||
# kill process names that might stil
|
||||
# be running from last time
|
||||
pkill gazebo
|
||||
pkill mainapp
|
||||
pkill px4
|
||||
jmavsim_pid=`jps | grep Simulator | cut -d" " -f1`
|
||||
if [ -n "$jmavsim_pid" ]
|
||||
then
|
||||
@@ -58,7 +58,7 @@ cp Tools/posix.gdbinit $build_path/src/firmware/posix/.gdbinit
|
||||
|
||||
SIM_PID=0
|
||||
|
||||
if [ "$program" == "jmavsim" ] && [ "$no_sim" == "" ]
|
||||
if [ "$program" == "jmavsim" ] && [ ! -n "$no_sim" ]
|
||||
then
|
||||
cd Tools/jMAVSim
|
||||
ant create_run_jar copy_res
|
||||
@@ -66,31 +66,33 @@ then
|
||||
java -Djava.ext.dirs= -jar jmavsim_run.jar -udp 127.0.0.1:14560 &
|
||||
SIM_PID=`echo $!`
|
||||
cd ../..
|
||||
elif [ "$program" == "gazebo" ] && [ "$no_sim" == "" ]
|
||||
elif [ "$program" == "gazebo" ] && [ ! -n "$no_sim" ]
|
||||
then
|
||||
if [ -x "$(command -v gazebo)" ]
|
||||
then
|
||||
# Set the plugin path so Gazebo finds our model and sim
|
||||
export GAZEBO_PLUGIN_PATH=$curr_dir/Tools/sitl_gazebo/Build:${GAZEBO_PLUGIN_PATH}
|
||||
export GAZEBO_PLUGIN_PATH=$curr_dir/build_gazebo:${GAZEBO_PLUGIN_PATH}
|
||||
# Set the model path so Gazebo finds the airframes
|
||||
export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:$curr_dir/Tools/sitl_gazebo/models
|
||||
# The next line would disable online model lookup, can be commented in, in case of unstable behaviour.
|
||||
# export GAZEBO_MODEL_DATABASE_URI=""
|
||||
export SITL_GAZEBO_PATH=$curr_dir/Tools/sitl_gazebo
|
||||
mkdir -p Tools/sitl_gazebo/Build
|
||||
cd Tools/sitl_gazebo/Build
|
||||
cmake -Wno-dev ..
|
||||
make -j4
|
||||
make sdf
|
||||
gzserver --verbose ../worlds/${model}.world &
|
||||
make --no-print-directory gazebo_build
|
||||
|
||||
gzserver --verbose $curr_dir/Tools/sitl_gazebo/worlds/${model}.world &
|
||||
SIM_PID=`echo $!`
|
||||
gzclient --verbose &
|
||||
GUI_PID=`echo $!`
|
||||
|
||||
if [[ -n "$HEADLESS" ]]; then
|
||||
echo "not running gazebo gui"
|
||||
else
|
||||
gzclient --verbose &
|
||||
GUI_PID=`echo $!`
|
||||
fi
|
||||
else
|
||||
echo "You need to have gazebo simulator installed!"
|
||||
exit 1
|
||||
fi
|
||||
elif [ "$program" == "replay" ] && [ "$no_sim" == "" ]
|
||||
elif [ "$program" == "replay" ] && [ ! -n "$no_sim" ]
|
||||
then
|
||||
echo "Replaying logfile: $logfile"
|
||||
# This is not a simulator, but a log file to replay
|
||||
@@ -115,18 +117,18 @@ set +e
|
||||
# Start Java simulator
|
||||
if [ "$debugger" == "lldb" ]
|
||||
then
|
||||
lldb -- mainapp ../../../../${rc_script}_${program}_${model}
|
||||
lldb -- px4 ../../../../${rc_script}_${program}_${model}
|
||||
elif [ "$debugger" == "gdb" ]
|
||||
then
|
||||
gdb --args mainapp ../../../../${rc_script}_${program}_${model}
|
||||
gdb --args px4 ../../../../${rc_script}_${program}_${model}
|
||||
elif [ "$debugger" == "ddd" ]
|
||||
then
|
||||
ddd --debugger gdb --args mainapp ../../../../${rc_script}_${program}_${model}
|
||||
ddd --debugger gdb --args px4 ../../../../${rc_script}_${program}_${model}
|
||||
elif [ "$debugger" == "valgrind" ]
|
||||
then
|
||||
valgrind ./mainapp ../../../../${rc_script}_${program}_${model}
|
||||
valgrind ./px4 ../../../../${rc_script}_${program}_${model}
|
||||
else
|
||||
$sudo_enabled ./mainapp $chroot_enabled ../../../../${rc_script}_${program}_${model}
|
||||
$sudo_enabled ./px4 $chroot_enabled ../../../../${rc_script}_${program}_${model}
|
||||
fi
|
||||
|
||||
if [ "$program" == "jmavsim" ]
|
||||
@@ -135,5 +137,7 @@ then
|
||||
elif [ "$program" == "gazebo" ]
|
||||
then
|
||||
kill -9 $SIM_PID
|
||||
kill -9 $GUI_PID
|
||||
if [[ ! -n "$HEADLESS" ]]; then
|
||||
kill -9 $GUI_PID
|
||||
fi
|
||||
fi
|
||||
|
||||
+2
-2
@@ -17,7 +17,7 @@ fi
|
||||
|
||||
if [ $SYSTYPE = "Linux" ];
|
||||
then
|
||||
SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*"
|
||||
SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/usb-The_Autopilot*"
|
||||
fi
|
||||
|
||||
if [ $SYSTYPE = "" ];
|
||||
@@ -25,4 +25,4 @@ then
|
||||
SERIAL_PORTS="COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0"
|
||||
fi
|
||||
|
||||
python $BASEDIR/px_uploader.py --port $SERIAL_PORTS $1
|
||||
python $BASEDIR/px_uploader.py --port $SERIAL_PORTS $1
|
||||
|
||||
+20
@@ -0,0 +1,20 @@
|
||||
machine:
|
||||
services:
|
||||
- docker
|
||||
|
||||
checkout:
|
||||
post:
|
||||
- git submodule sync --recursive
|
||||
- git submodule update --init --recursive
|
||||
|
||||
## Customize dependencies
|
||||
dependencies:
|
||||
cache_directories:
|
||||
- "~/.ccache"
|
||||
pre:
|
||||
- docker pull px4io/px4-dev-nuttx-gcc4.9
|
||||
|
||||
test:
|
||||
override:
|
||||
- docker run --rm -v `pwd`:`pwd`:rw -w=`pwd` -v $HOME/.ccache:$HOME/.ccache:rw -e CCACHE_DIR=$HOME/.ccache --user=$UID -it px4io/px4-dev-nuttx-gcc4.9 /bin/bash -c "ccache -z; make px4fmu-v4_default; ccache -s"
|
||||
|
||||
+1
-1
Submodule cmake/cmake_hexagon updated: 77d487dc07...eb1d242e57
+95
-16
@@ -303,6 +303,9 @@ function(px4_add_module)
|
||||
if(MAIN)
|
||||
set_target_properties(${MODULE} PROPERTIES
|
||||
COMPILE_DEFINITIONS PX4_MAIN=${MAIN}_app_main)
|
||||
add_definitions(-DMODULE_NAME="${MAIN}")
|
||||
else()
|
||||
add_definitions(-DMODULE_NAME="${MODULE}")
|
||||
endif()
|
||||
|
||||
if(INCLUDES)
|
||||
@@ -359,13 +362,15 @@ function(px4_generate_messages)
|
||||
NAME px4_generate_messages
|
||||
OPTIONS VERBOSE
|
||||
ONE_VALUE OS TARGET
|
||||
MULTI_VALUE MSG_FILES DEPENDS
|
||||
MULTI_VALUE MSG_FILES DEPENDS INCLUDES
|
||||
REQUIRED MSG_FILES OS TARGET
|
||||
ARGN ${ARGN})
|
||||
set(QUIET)
|
||||
if(NOT VERBOSE)
|
||||
set(QUIET "-q")
|
||||
endif()
|
||||
|
||||
# headers
|
||||
set(msg_out_path ${CMAKE_BINARY_DIR}/src/modules/uORB/topics)
|
||||
set(msg_list)
|
||||
foreach(msg_file ${MSG_FILES})
|
||||
@@ -378,18 +383,48 @@ function(px4_generate_messages)
|
||||
endforeach()
|
||||
add_custom_command(OUTPUT ${msg_files_out}
|
||||
COMMAND ${PYTHON_EXECUTABLE}
|
||||
Tools/px_generate_uorb_topic_headers.py
|
||||
Tools/px_generate_uorb_topic_files.py
|
||||
--headers
|
||||
${QUIET}
|
||||
-d msg
|
||||
-o ${msg_out_path}
|
||||
-e msg/templates/uorb
|
||||
-t ${CMAKE_BINARY_DIR}/topics_temporary
|
||||
-t ${CMAKE_BINARY_DIR}/topics_temporary_header
|
||||
DEPENDS ${DEPENDS} ${MSG_FILES}
|
||||
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
|
||||
COMMENT "Generating uORB topic headers"
|
||||
VERBATIM
|
||||
)
|
||||
|
||||
# !sources
|
||||
set(msg_source_out_path ${CMAKE_BINARY_DIR}/topics_sources)
|
||||
set(msg_source_files_out ${msg_source_out_path}/uORBTopics.cpp)
|
||||
foreach(msg ${msg_list})
|
||||
list(APPEND msg_source_files_out ${msg_source_out_path}/${msg}.cpp)
|
||||
endforeach()
|
||||
add_custom_command(OUTPUT ${msg_source_files_out}
|
||||
COMMAND ${PYTHON_EXECUTABLE}
|
||||
Tools/px_generate_uorb_topic_files.py
|
||||
--sources
|
||||
${QUIET}
|
||||
-d msg
|
||||
-o ${msg_source_out_path}
|
||||
-e msg/templates/uorb
|
||||
-t ${CMAKE_BINARY_DIR}/topics_temporary_sources
|
||||
DEPENDS ${DEPENDS} ${MSG_FILES}
|
||||
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
|
||||
COMMENT "Generating uORB topic sources"
|
||||
VERBATIM
|
||||
)
|
||||
set_source_files_properties(${msg_source_files_out} PROPERTIES GENERATED TRUE)
|
||||
|
||||
# We remove uORBTopics.cpp to make sure the generator is re-run, which is
|
||||
# necessary when a .msg file is removed and because uORBTopics.cpp depends
|
||||
# on all topics.
|
||||
execute_process(COMMAND rm uORBTopics.cpp
|
||||
WORKING_DIRECTORY ${msg_source_out_path}
|
||||
ERROR_QUIET)
|
||||
|
||||
# multi messages for target OS
|
||||
set(msg_multi_out_path
|
||||
${CMAKE_BINARY_DIR}/src/platforms/${OS}/px4_messages)
|
||||
@@ -399,7 +434,8 @@ function(px4_generate_messages)
|
||||
endforeach()
|
||||
add_custom_command(OUTPUT ${msg_multi_files_out}
|
||||
COMMAND ${PYTHON_EXECUTABLE}
|
||||
Tools/px_generate_uorb_topic_headers.py
|
||||
Tools/px_generate_uorb_topic_files.py
|
||||
--headers
|
||||
${QUIET}
|
||||
-d msg
|
||||
-o ${msg_multi_out_path}
|
||||
@@ -411,8 +447,13 @@ function(px4_generate_messages)
|
||||
COMMENT "Generating uORB topic multi headers for ${OS}"
|
||||
VERBATIM
|
||||
)
|
||||
add_custom_target(${TARGET}
|
||||
DEPENDS ${msg_multi_files_out} ${msg_files_out})
|
||||
|
||||
add_library(${TARGET}
|
||||
${msg_source_files_out}
|
||||
${msg_multi_files_out}
|
||||
${msg_files_out}
|
||||
)
|
||||
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
@@ -447,6 +488,7 @@ function(px4_add_upload)
|
||||
if(${CMAKE_HOST_SYSTEM_NAME} STREQUAL "Linux")
|
||||
list(APPEND serial_ports
|
||||
/dev/serial/by-id/usb-3D_Robotics*
|
||||
/dev/serial/by-id/usb-The_Autopilot*
|
||||
/dev/serial/by-id/pci-3D_Robotics*
|
||||
)
|
||||
elseif(${CMAKE_HOST_SYSTEM_NAME} STREQUAL "Darwin")
|
||||
@@ -490,6 +532,42 @@ function(px4_add_adb_push)
|
||||
)
|
||||
endfunction()
|
||||
|
||||
function(px4_add_adb_push_to_bebop)
|
||||
px4_parse_function_args(
|
||||
NAME px4_add_upload_to_bebop
|
||||
ONE_VALUE OS BOARD OUT DEST
|
||||
MULTI_VALUE FILES DEPENDS
|
||||
REQUIRED OS BOARD OUT FILES DEPENDS DEST
|
||||
ARGN ${ARGN})
|
||||
|
||||
add_custom_target(${OUT}
|
||||
COMMAND ${CMAKE_SOURCE_DIR}/Tools/adb_upload_to_bebop.sh ${FILES} ${DEST}
|
||||
DEPENDS ${DEPENDS}
|
||||
WORKING_DIRECTORY ${CMAKE_BINARY_DIR}
|
||||
COMMENT "uploading ${BUNDLE}"
|
||||
VERBATIM
|
||||
USES_TERMINAL
|
||||
)
|
||||
endfunction()
|
||||
|
||||
function(px4_add_scp_push)
|
||||
px4_parse_function_args(
|
||||
NAME px4_add_upload
|
||||
ONE_VALUE OS BOARD OUT DEST
|
||||
MULTI_VALUE FILES DEPENDS
|
||||
REQUIRED OS BOARD OUT FILES DEPENDS DEST
|
||||
ARGN ${ARGN})
|
||||
|
||||
add_custom_target(${OUT}
|
||||
COMMAND ${CMAKE_SOURCE_DIR}/Tools/scp_upload.sh ${FILES} ${DEST}
|
||||
DEPENDS ${DEPENDS}
|
||||
WORKING_DIRECTORY ${CMAKE_BINARY_DIR}
|
||||
COMMENT "uploading ${BUNDLE}"
|
||||
VERBATIM
|
||||
USES_TERMINAL
|
||||
)
|
||||
endfunction()
|
||||
|
||||
|
||||
#=============================================================================
|
||||
#
|
||||
@@ -541,7 +619,6 @@ function(px4_add_common_flags)
|
||||
-Wall
|
||||
-Werror
|
||||
-Wextra
|
||||
-Wpacked
|
||||
-Wno-sign-compare
|
||||
-Wshadow
|
||||
-Wfloat-equal
|
||||
@@ -583,7 +660,8 @@ function(px4_add_common_flags)
|
||||
endif()
|
||||
|
||||
if ($ENV{MEMORY_DEBUG} MATCHES "1")
|
||||
set(max_optimization -O0)
|
||||
message(STATUS "address sanitizer enabled")
|
||||
set(max_optimization -Os)
|
||||
|
||||
set(optimization_flags
|
||||
-fno-strict-aliasing
|
||||
@@ -591,7 +669,7 @@ function(px4_add_common_flags)
|
||||
-funsafe-math-optimizations
|
||||
-ffunction-sections
|
||||
-fdata-sections
|
||||
-g -fsanitize=address
|
||||
-g3 -fsanitize=address
|
||||
)
|
||||
else()
|
||||
set(max_optimization -Os)
|
||||
@@ -710,6 +788,7 @@ function(px4_add_common_flags)
|
||||
string(REPLACE "-" "_" board_config ${board_upper})
|
||||
set(added_definitions
|
||||
-DCONFIG_ARCH_BOARD_${board_config}
|
||||
-D__STDC_FORMAT_MACROS
|
||||
)
|
||||
|
||||
if (NOT (APPLE AND (${CMAKE_C_COMPILER_ID} MATCHES ".*Clang.*")))
|
||||
@@ -776,21 +855,21 @@ function(px4_create_git_hash_header)
|
||||
REQUIRED HEADER
|
||||
ARGN ${ARGN})
|
||||
execute_process(
|
||||
COMMAND git describe --tags
|
||||
COMMAND git describe --always --tags
|
||||
OUTPUT_VARIABLE git_tag
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
|
||||
)
|
||||
#message(STATUS "GIT_TAG = ${git_tag}")
|
||||
message(STATUS "GIT_TAG = ${git_tag}")
|
||||
execute_process(
|
||||
COMMAND git rev-parse HEAD
|
||||
OUTPUT_VARIABLE git_desc
|
||||
COMMAND git rev-parse --verify HEAD
|
||||
OUTPUT_VARIABLE git_version
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
|
||||
)
|
||||
#message(STATUS "GIT_DESC = ${git_desc}")
|
||||
set(git_desc_short)
|
||||
string(SUBSTRING ${git_desc} 1 16 git_desc_short)
|
||||
#message(STATUS "GIT_VERSION = ${git_version}")
|
||||
set(git_version_short)
|
||||
string(SUBSTRING ${git_version} 1 16 git_version_short)
|
||||
configure_file(${CMAKE_SOURCE_DIR}/cmake/templates/build_git_version.h.in ${HEADER} @ONLY)
|
||||
endfunction()
|
||||
|
||||
|
||||
@@ -15,7 +15,7 @@ set(config_module_list
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
#drivers/px4io
|
||||
drivers/test_ppm
|
||||
#drivers/test_ppm
|
||||
drivers/boards/mindpx-v2
|
||||
#drivers/rgbled
|
||||
drivers/rgbled_pwm
|
||||
@@ -64,18 +64,33 @@ set(config_module_list
|
||||
systemcmds/pwm
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
#systemcmds/topic_listener
|
||||
systemcmds/topic_listener
|
||||
systemcmds/top
|
||||
systemcmds/config
|
||||
systemcmds/nshterm
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
systemcmds/sd_bench
|
||||
systemcmds/motor_ramp
|
||||
|
||||
#
|
||||
# Tests
|
||||
#
|
||||
drivers/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
modules/commander/commander_tests
|
||||
modules/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
@@ -85,16 +100,15 @@ set(config_module_list
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
# Too high RAM usage due to static allocations
|
||||
# modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
# modules/segway # XXX Needs GCC 4.7 fix
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
@@ -105,6 +119,7 @@ set(config_module_list
|
||||
# Logging
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
@@ -134,7 +149,7 @@ set(config_module_list
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
|
||||
#
|
||||
@@ -145,7 +160,7 @@ set(config_module_list
|
||||
#
|
||||
# Rover apps
|
||||
#
|
||||
examples/rover_steering_control
|
||||
#examples/rover_steering_control
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
@@ -153,7 +168,7 @@ set(config_module_list
|
||||
#examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/px4_simple_app
|
||||
examples/px4_simple_app
|
||||
#examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/daemon
|
||||
@@ -176,10 +191,6 @@ set(config_extra_builtin_cmds
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_io_board
|
||||
px4io-v2
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
uavcan
|
||||
uavcan_stm32_driver
|
||||
@@ -191,9 +202,11 @@ set(config_io_extra_libs
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon" STACK_MAIN "2048")
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis" STACK_MAIN "2048")
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
@@ -61,6 +61,7 @@ set(config_module_list
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
@@ -90,6 +91,7 @@ set(config_module_list
|
||||
# Logging
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
|
||||
@@ -48,33 +48,48 @@ set(config_module_list
|
||||
drivers/bst
|
||||
drivers/snapdragon_rc_pwm
|
||||
drivers/lis3mdl
|
||||
drivers/bmi160
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
#systemcmds/esc_calib
|
||||
systemcmds/mixer
|
||||
#systemcmds/motor_ramp
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
#systemcmds/topic_listener
|
||||
#systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
systemcmds/config
|
||||
systemcmds/nshterm
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
#systemcmds/topic_listener
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
#drivers/sf0x/sf0x_tests
|
||||
#drivers/test_ppm
|
||||
#lib/rc/rc_tests
|
||||
#modules/commander/commander_tests
|
||||
#modules/controllib_test
|
||||
#modules/mavlink/mavlink_tests
|
||||
#modules/unit_test
|
||||
#modules/uORB/uORB_tests
|
||||
#systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
#modules/gpio_led
|
||||
modules/uavcan
|
||||
modules/land_detector
|
||||
|
||||
@@ -82,14 +97,14 @@ set(config_module_list
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf_att_pos_estimator
|
||||
#modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
# modules/segway # XXX Needs GCC 4.7 fix
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
@@ -99,6 +114,7 @@ set(config_module_list
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
#modules/logger
|
||||
modules/sdlog2
|
||||
|
||||
#
|
||||
|
||||
@@ -41,11 +41,13 @@ set(config_module_list
|
||||
modules/sensors
|
||||
#drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
drivers/oreoled
|
||||
#drivers/oreoled
|
||||
drivers/gimbal
|
||||
drivers/pwm_input
|
||||
drivers/camera_trigger
|
||||
drivers/bst
|
||||
#drivers/snapdragon_rc_pwm
|
||||
#drivers/lis3mdl
|
||||
|
||||
#
|
||||
# System commands
|
||||
@@ -64,25 +66,25 @@ set(config_module_list
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
#systemcmds/sd_bench
|
||||
#systemcmds/tests
|
||||
systemcmds/motor_ramp
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
#modules/gpio_led
|
||||
modules/uavcan
|
||||
modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
# Too high RAM usage due to static allocations
|
||||
# modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf2
|
||||
modules/position_estimator_inav
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
@@ -97,6 +99,7 @@ set(config_module_list
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
modules/sdlog2
|
||||
|
||||
#
|
||||
@@ -138,7 +141,7 @@ set(config_module_list
|
||||
#
|
||||
# Rover apps
|
||||
#
|
||||
examples/rover_steering_control
|
||||
#examples/rover_steering_control
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
|
||||
@@ -0,0 +1,210 @@
|
||||
include(nuttx/px4_impl_nuttx)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
|
||||
|
||||
set(config_uavcan_num_ifaces 2)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/boards/px4fmu-v2
|
||||
drivers/rgbled
|
||||
drivers/mpu6000
|
||||
drivers/mpu9250
|
||||
drivers/lsm303d
|
||||
drivers/l3gd20
|
||||
drivers/hmc5883
|
||||
drivers/ms5611
|
||||
#drivers/mb12xx
|
||||
#drivers/srf02
|
||||
#drivers/sf0x
|
||||
#drivers/ll40ls
|
||||
#drivers/trone
|
||||
drivers/gps
|
||||
#drivers/pwm_out_sim
|
||||
#drivers/hott
|
||||
#drivers/hott/hott_telemetry
|
||||
#drivers/hott/hott_sensors
|
||||
drivers/blinkm
|
||||
drivers/airspeed
|
||||
drivers/ets_airspeed
|
||||
drivers/meas_airspeed
|
||||
drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
#drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
#drivers/oreoled
|
||||
drivers/gimbal
|
||||
drivers/pwm_input
|
||||
drivers/camera_trigger
|
||||
#drivers/bst
|
||||
#drivers/snapdragon_rc_pwm
|
||||
#drivers/lis3mdl
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
#systemcmds/esc_calib
|
||||
systemcmds/mixer
|
||||
systemcmds/motor_ramp
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/reboot
|
||||
#systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
#systemcmds/topic_listener
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
#lib/rc/rc_tests
|
||||
modules/commander/commander_tests
|
||||
modules/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
#modules/gpio_led
|
||||
modules/uavcan
|
||||
modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
#modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
#modules/logger
|
||||
#modules/sdlog2
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
|
||||
#
|
||||
# OBC challenge
|
||||
#
|
||||
#modules/bottle_drop
|
||||
|
||||
#
|
||||
# Rover apps
|
||||
#
|
||||
#examples/rover_steering_control
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/px4_simple_app
|
||||
#examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/daemon
|
||||
#examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/debug_values
|
||||
#examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/example_fixedwing_control
|
||||
#examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#examples/hwtest
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_io_board
|
||||
px4io-v2
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
uavcan
|
||||
uavcan_stm32_driver
|
||||
)
|
||||
|
||||
set(config_io_extra_libs
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon" STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis" STACK_MAIN "2048")
|
||||
@@ -23,6 +23,7 @@ set(config_module_list
|
||||
drivers/mb12xx
|
||||
drivers/srf02
|
||||
drivers/sf0x
|
||||
drivers/sf1xx
|
||||
drivers/ll40ls
|
||||
drivers/trone
|
||||
drivers/gps
|
||||
@@ -45,6 +46,10 @@ set(config_module_list
|
||||
drivers/bst
|
||||
drivers/snapdragon_rc_pwm
|
||||
drivers/lis3mdl
|
||||
drivers/bmp280
|
||||
drivers/bma180
|
||||
drivers/bmi160
|
||||
drivers/tap_esc
|
||||
|
||||
#
|
||||
# System commands
|
||||
@@ -63,12 +68,26 @@ set(config_module_list
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
systemcmds/sd_bench
|
||||
systemcmds/motor_ramp
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
modules/commander/commander_tests
|
||||
modules/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
@@ -78,12 +97,11 @@ set(config_module_list
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
# Too high RAM usage due to static allocations
|
||||
# modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/ekf2
|
||||
modules/local_position_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
@@ -99,6 +117,7 @@ set(config_module_list
|
||||
# Logging
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
|
||||
@@ -0,0 +1,129 @@
|
||||
include(nuttx/px4_impl_nuttx)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
drivers/boards/tap-v1
|
||||
drivers/rgbled_pwm
|
||||
drivers/tap_esc
|
||||
#drivers/mpu6500
|
||||
drivers/ms5611
|
||||
drivers/hmc5883
|
||||
drivers/gps
|
||||
drivers/airspeed
|
||||
drivers/meas_airspeed
|
||||
modules/sensors
|
||||
drivers/camera_trigger
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/motor_test
|
||||
systemcmds/reboot
|
||||
systemcmds/top
|
||||
systemcmds/config
|
||||
systemcmds/nshterm
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
systemcmds/topic_listener
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_io_board
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
)
|
||||
|
||||
set(config_io_extra_libs
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
@@ -1,57 +1,106 @@
|
||||
include(posix/px4_impl_posix)
|
||||
|
||||
if ("${RPI_TOOLCHAIN_DIR}" STREQUAL "")
|
||||
set(RPI_TOOLCHAIN_DIR /opt/rpi_toolchain)
|
||||
endif()
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake)
|
||||
|
||||
set(CMAKE_PROGRAM_PATH
|
||||
add_definitions(
|
||||
-D__PX4_POSIX_BEBOP
|
||||
-D__LINUX
|
||||
-D__BEBOP
|
||||
)
|
||||
|
||||
set(CMAKE_PROGRAM_PATH
|
||||
"${RPI_TOOLCHAIN_DIR}/gcc-linaro-arm-linux-gnueabihf-raspbian/bin"
|
||||
${CMAKE_PROGRAM_PATH}
|
||||
)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake)
|
||||
|
||||
set(config_module_list
|
||||
|
||||
# examples/px4_simple_app
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_ms5607_wrapper
|
||||
platforms/posix/drivers/df_mpu6050_wrapper
|
||||
platforms/posix/drivers/df_ak8963_wrapper
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
#modules/attitude_estimator_ekf
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/commander
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/mavlink
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
modules/land_detector
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
|
||||
#
|
||||
# PX4 drivers
|
||||
#
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/ecl
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/external_lgpl
|
||||
lib/conversion
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# POSIX
|
||||
#
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
)
|
||||
|
||||
set(config_df_driver_list
|
||||
ms5607
|
||||
mpu6050
|
||||
ak8963
|
||||
)
|
||||
@@ -27,6 +27,7 @@ set(config_module_list
|
||||
modules/sensors
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/simulator
|
||||
modules/commander
|
||||
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
include(posix/px4_impl_posix)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-arm-linux-gnueabihf.cmake)
|
||||
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon")
|
||||
|
||||
@@ -12,7 +12,7 @@ set(CONFIG_SHMEM "1")
|
||||
# or if it is for the Snapdragon.
|
||||
add_definitions(
|
||||
-D__PX4_POSIX_EAGLE
|
||||
-D__USING_SNAPDRAGON_LEGACY_DRIVER
|
||||
-D__USING_SNAPDRAGON_LEGACY_DRIVER
|
||||
)
|
||||
|
||||
set(config_module_list
|
||||
@@ -45,8 +45,10 @@ set(config_module_list
|
||||
modules/sensors
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/simulator
|
||||
modules/commander
|
||||
modules/navigator
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
|
||||
@@ -1,48 +0,0 @@
|
||||
include(posix/px4_impl_posix)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
|
||||
set(config_module_list
|
||||
drivers/device
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/mavlink
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
)
|
||||
@@ -0,0 +1,114 @@
|
||||
# This file is shared between posix_rpi_native.cmake
|
||||
# and posix_rpi_cross.cmake.
|
||||
|
||||
include(posix/px4_impl_posix)
|
||||
|
||||
# This definition allows to differentiate if this just the usual POSIX build
|
||||
# or if it is for the RPi.
|
||||
add_definitions(
|
||||
-D__PX4_POSIX_RPI
|
||||
-D__LINUX
|
||||
)
|
||||
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_mpu9250_wrapper
|
||||
platforms/posix/drivers/df_lsm9ds1_wrapper
|
||||
platforms/posix/drivers/df_ms5611_wrapper
|
||||
platforms/posix/drivers/df_hmc5883_wrapper
|
||||
platforms/posix/drivers/df_trone_wrapper
|
||||
platforms/posix/drivers/df_isl29501_wrapper
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
#modules/attitude_estimator_ekf
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/commander
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
modules/land_detector
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
|
||||
#
|
||||
# PX4 drivers
|
||||
#
|
||||
drivers/gps
|
||||
drivers/navio_sysfs_rc_in
|
||||
drivers/navio_sysfs_pwm_out
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/geo
|
||||
lib/ecl
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/external_lgpl
|
||||
lib/conversion
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
# POSIX
|
||||
#
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
)
|
||||
|
||||
#
|
||||
# DriverFramework driver
|
||||
#
|
||||
set(config_df_driver_list
|
||||
mpu9250
|
||||
lsm9ds1
|
||||
ms5611
|
||||
hmc5883
|
||||
trone
|
||||
isl29501
|
||||
)
|
||||
@@ -0,0 +1,8 @@
|
||||
include(configs/posix_rpi_common)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf-raspbian.cmake)
|
||||
|
||||
set(CMAKE_PROGRAM_PATH
|
||||
"${RPI_TOOLCHAIN_DIR}/gcc-linaro-arm-linux-gnueabihf-raspbian/bin"
|
||||
${CMAKE_PROGRAM_PATH}
|
||||
)
|
||||
@@ -0,0 +1,3 @@
|
||||
include(configs/posix_rpi_common)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
@@ -38,8 +38,10 @@ set(config_module_list
|
||||
modules/sensors
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/simulator
|
||||
modules/commander
|
||||
modules/navigator
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
|
||||
@@ -49,6 +49,7 @@ set(config_module_list
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
modules/commander
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
|
||||
@@ -3,67 +3,92 @@ include(posix/px4_impl_posix)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
|
||||
set(config_module_list
|
||||
drivers/device
|
||||
drivers/boards/sitl
|
||||
drivers/pwm_out_sim
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/gpssim
|
||||
drivers/device
|
||||
drivers/gps
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
drivers/pwm_out_sim
|
||||
|
||||
platforms/common
|
||||
platforms/posix/drivers/accelsim
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/airspeedsim
|
||||
platforms/posix/drivers/barosim
|
||||
platforms/posix/drivers/gpssim
|
||||
platforms/posix/drivers/gyrosim
|
||||
platforms/posix/drivers/rgbledsim
|
||||
platforms/posix/drivers/ledsim
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
platforms/posix/drivers/rgbledsim
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
|
||||
systemcmds/esc_calib
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/mavlink
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/topic_listener
|
||||
systemcmds/ver
|
||||
systemcmds/top
|
||||
systemcmds/motor_ramp
|
||||
|
||||
modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/commander
|
||||
modules/dataman
|
||||
modules/ekf2
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/land_detector
|
||||
modules/logger
|
||||
modules/mavlink
|
||||
modules/mc_att_control
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/mc_pos_control
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/navigator
|
||||
modules/param
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/replay
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/vtol_att_control
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/rc
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
lib/terrain_estimation
|
||||
|
||||
examples/px4_simple_app
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/sf0x/sf0x_tests
|
||||
lib/rc/rc_tests
|
||||
modules/commander/commander_tests
|
||||
modules/controllib_test
|
||||
#modules/mavlink/mavlink_tests #TODO: fix mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
@@ -89,3 +114,12 @@ set(config_sitl_debugger
|
||||
)
|
||||
set_property(CACHE config_sitl_debugger
|
||||
PROPERTY STRINGS "disable;gdb;lldb")
|
||||
|
||||
# If the environment variable 'replay' is defined, we are building with replay
|
||||
# support. In this case, we enable the orb publisher rules.
|
||||
set(REPLAY_FILE "$ENV{replay}")
|
||||
if(REPLAY_FILE)
|
||||
message("Building with uorb publisher rules support")
|
||||
add_definitions(-DORB_USE_PUBLISHER_RULES)
|
||||
endif()
|
||||
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user