diff --git a/CMakeLists.txt b/CMakeLists.txt index 918e5bd875..351a0f6c36 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -219,7 +219,6 @@ px4_add_git_submodule(TARGET git_gtest PATH "unittets/gtest") px4_add_git_submodule(TARGET git_uavcan PATH "src/lib/uavcan") px4_add_git_submodule(TARGET git_eigen PATH "src/lib/eigen") px4_add_git_submodule(TARGET git_nuttx PATH "NuttX") -px4_add_git_submodule(TARGET git_eigen32 PATH "src/lib/eigen-3.2") px4_add_git_submodule(TARGET git_dspal PATH "src/lib/dspal") add_custom_target(submodule_clean diff --git a/cmake/common/px4_base.cmake b/cmake/common/px4_base.cmake index 54ab915bfd..1de4dddb01 100644 --- a/cmake/common/px4_base.cmake +++ b/cmake/common/px4_base.cmake @@ -486,7 +486,6 @@ function(px4_add_common_flags) -Wextra #-Wshadow # very verbose due to eigen -Wfloat-equal - -Wframe-larger-than=1024 -Wpointer-arith -Wmissing-declarations -Wpacked @@ -506,10 +505,17 @@ function(px4_add_common_flags) # but generates too many false positives ) + if (NOT ${OS} STREQUAL "qurt") + list(APPEND warnings -Wframe-larger-than=1024) + endif() + if (${CMAKE_C_COMPILER_ID} STREQUAL "Clang") - list(APPEND warnings - -Wno-unused-const-variable - ) + # QuRT 6.4.X compiler identifies as Clang but does not support this option + if (NOT ${OS} STREQUAL "qurt") + list(APPEND warnings + -Wno-unused-const-variable + ) + endif() else() list(APPEND warnings -Werror=unused-but-set-variable @@ -609,11 +615,9 @@ function(px4_add_common_flags) ${CMAKE_SOURCE_DIR}/mavlink/include/mavlink ) - if (NOT ${OS} STREQUAL "qurt") - list(APPEND added_include_dirs - ${CMAKE_SOURCE_DIR}/src/lib/eigen - ) - endif() + list(APPEND added_include_dirs + src/lib/eigen + ) set(added_link_dirs) # none used currently diff --git a/cmake/configs/qurt_eagle_hello.cmake b/cmake/configs/qurt_eagle_hello.cmake index 45ae2b22ed..5b38a70649 100644 --- a/cmake/configs/qurt_eagle_hello.cmake +++ b/cmake/configs/qurt_eagle_hello.cmake @@ -1,6 +1,6 @@ include(qurt/px4_impl_qurt) -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list drivers/device diff --git a/cmake/configs/qurt_eagle_hil.cmake b/cmake/configs/qurt_eagle_hil.cmake index bab551262d..6bb9e0cbc3 100644 --- a/cmake/configs/qurt_eagle_hil.cmake +++ b/cmake/configs/qurt_eagle_hil.cmake @@ -1,6 +1,6 @@ include(qurt/px4_impl_qurt) -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list drivers/device diff --git a/cmake/configs/qurt_eagle_muorb.cmake b/cmake/configs/qurt_eagle_muorb.cmake index afdc35dad5..6f4f12cf4d 100644 --- a/cmake/configs/qurt_eagle_muorb.cmake +++ b/cmake/configs/qurt_eagle_muorb.cmake @@ -1,6 +1,6 @@ include(qurt/px4_impl_qurt) -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list drivers/device diff --git a/cmake/configs/qurt_eagle_release.cmake b/cmake/configs/qurt_eagle_release.cmake index 0b03dcea48..f80c87d5fb 100644 --- a/cmake/configs/qurt_eagle_release.cmake +++ b/cmake/configs/qurt_eagle_release.cmake @@ -20,7 +20,7 @@ set(target_libraries ) -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list # diff --git a/cmake/configs/qurt_eagle_test.cmake b/cmake/configs/qurt_eagle_test.cmake index 5e9cffc407..6f948d905c 100644 --- a/cmake/configs/qurt_eagle_test.cmake +++ b/cmake/configs/qurt_eagle_test.cmake @@ -1,6 +1,6 @@ include(qurt/px4_impl_qurt) -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list drivers/device diff --git a/cmake/configs/qurt_eagle_travis.cmake b/cmake/configs/qurt_eagle_travis.cmake index 15593df251..20293830e2 100644 --- a/cmake/configs/qurt_eagle_travis.cmake +++ b/cmake/configs/qurt_eagle_travis.cmake @@ -3,7 +3,7 @@ include(qurt/px4_impl_qurt) # Run a full link with build stubs to make sure qurt target isn't broken set(QURT_ENABLE_STUBS "1") -set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon.cmake) +set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-hexagon-7.4.cmake) set(config_module_list drivers/device @@ -41,6 +41,7 @@ set(config_module_list modules/systemlib/mixer modules/uORB modules/commander + modules/controllib # # Libraries @@ -50,7 +51,7 @@ set(config_module_list lib/geo lib/geo_lookup lib/conversion - modules/controllib + lib/ecl # # QuRT port diff --git a/cmake/qurt/px4_impl_qurt.cmake b/cmake/qurt/px4_impl_qurt.cmake index d565210dfd..6f15a640f3 100644 --- a/cmake/qurt/px4_impl_qurt.cmake +++ b/cmake/qurt/px4_impl_qurt.cmake @@ -167,7 +167,6 @@ function(px4_os_add_flags) ${DSPAL_ROOT}/uart_esc/inc src/platforms/qurt/include src/platforms/posix/include - src/lib/eigen-3.2 ) set(added_definitions @@ -223,11 +222,14 @@ function(px4_os_prebuild_targets) ONE_VALUE OUT BOARD THREADS REQUIRED OUT BOARD ARGN ${ARGN}) - add_custom_target(${OUT} DEPENDS git_dspal git_eigen32) - add_custom_target(ALL DEPENDS git_eigen32) - execute_process( - WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}/src/lib/eigen-3.2 - COMMAND patch -p1 -i ../../../cmake/qurt/qurt_eigen.patch) + add_custom_target(git_eigen_patched + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}/src/lib/eigen + COMMAND git checkout . + COMMAND patch -p1 -i ${CMAKE_SOURCE_DIR}/cmake/qurt/qurt_eigen.patch + DEPENDS git_eigen) + add_custom_target(${OUT} DEPENDS git_dspal git_eigen_patched) + add_custom_target(ALL DEPENDS git_eigen) + endfunction() # vim: set noet fenc=utf-8 ff=unix nowrap: diff --git a/cmake/qurt/qurt_eigen.patch b/cmake/qurt/qurt_eigen.patch index 9ea57403ba..3b3e76d6ad 100644 --- a/cmake/qurt/qurt_eigen.patch +++ b/cmake/qurt/qurt_eigen.patch @@ -1,17 +1,37 @@ -This patch is required for QuRT. complex.h defines "I" and it replaces "I" in the -enum definition without this patch creating an error. - -diff --git a/Eigen/src/Core/SolveTriangular.h b/Eigen/src/Core/SolveTriangular.h -index ef17f28..1116270 100644 ---- a/Eigen/src/Core/SolveTriangular.h -+++ b/Eigen/src/Core/SolveTriangular.h -@@ -112,6 +112,9 @@ template - struct triangular_solver_unroller; +diff --git a/Eigen/src/Core/util/Macros.h b/Eigen/src/Core/util/Macros.h +index 1ca1d66..9bc928b 100644 +--- a/Eigen/src/Core/util/Macros.h ++++ b/Eigen/src/Core/util/Macros.h +@@ -194,6 +194,12 @@ + #define EIGEN_ARCH_PPC 0 + #endif -+#ifdef __PX4_QURT -+#undef I ++/// \internal EIGEN_ARCH_HEXAGON set to 1 if the architecture is Hexagon ++#ifdef __HEXAGON_ARCH__ ++ #define EIGEN_ARCH_HEXAGON 1 ++#else ++ #define EIGEN_ARCH_HEXAGON 0 +#endif - template - struct triangular_solver_unroller { - enum { + + + // Operating system identification, EIGEN_OS_* +@@ -334,15 +340,16 @@ + #endif + + // Do we support r-value references? +-#if (__has_feature(cxx_rvalue_references) || \ ++#if ((__has_feature(cxx_rvalue_references) || \ + (defined(__cplusplus) && __cplusplus >= 201103L) || \ + defined(__GXX_EXPERIMENTAL_CXX0X__) || \ +- (EIGEN_COMP_MSVC >= 1600)) ++ (EIGEN_COMP_MSVC >= 1600)) && (!defined(EIGEN_ARCH_HEXAGON))) + #define EIGEN_HAVE_RVALUE_REFERENCES + #endif + + // Does the compiler support result_of? +-#if (__has_feature(cxx_lambdas) || (defined(__cplusplus) && __cplusplus >= 201103L)) ++#if ((__has_feature(cxx_lambdas) || (defined(__cplusplus) && __cplusplus >= 201103L)) && \ ++ (!defined(EIGEN_ARCH_HEXAGON))) + #define EIGEN_HAS_STD_RESULT_OF 1 + #endif + diff --git a/cmake/toolchains/Toolchain-hexagon-7.4.cmake b/cmake/toolchains/Toolchain-hexagon-7.4.cmake new file mode 100644 index 0000000000..9c4286044d --- /dev/null +++ b/cmake/toolchains/Toolchain-hexagon-7.4.cmake @@ -0,0 +1,240 @@ +# +# Copyright (C) 2015 Mark Charlebois. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +include(CMakeForceCompiler) + +list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake) +include(common/px4_base) + +if(NOT HEXAGON_TOOLS_ROOT) + set(HEXAGON_TOOLS_ROOT /opt/7.4/Tools) +endif() + +macro (list2string out in) + set(list ${ARGV}) + list(REMOVE_ITEM list ${out}) + foreach(item ${list}) + set(${out} "${${out}} ${item}") + endforeach() +endmacro(list2string) + +set(V_ARCH "v5") +set(CROSSDEV "hexagon-") +set(HEXAGON_BIN ${HEXAGON_TOOLS_ROOT}/bin) +set(HEXAGON_LIB_DIR ${HEXAGON_TOOLS_ROOT}/gnu/hexagon/lib) +set(HEXAGON_ISS_DIR ${HEXAGON_TOOLS_ROOT}/lib/iss) +set(TOOLSLIB ${HEXAGON_TOOLS_ROOT}/target/hexagon/lib/${V_ARCH}/G0) + +# Use the HexagonTools compiler (6.4.05) +set(CMAKE_C_COMPILER ${HEXAGON_BIN}/${CROSSDEV}clang) +set(CMAKE_CXX_COMPILER ${HEXAGON_BIN}/${CROSSDEV}clang++) + +set(CMAKE_AR ${HEXAGON_BIN}/${CROSSDEV}ar CACHE FILEPATH "Archiver") +set(CMAKE_RANLIB ${HEXAGON_BIN}/${CROSSDEV}ranlib) +set(CMAKE_LINKER ${HEXAGON_BIN}/${CROSSDEV}ld.qcld) +set(CMAKE_NM ${HEXAGON_BIN}/${CROSSDEV}nm) +set(CMAKE_OBJDUMP ${HEXAGON_BIN}/${CROSSDEV}objdump) +set(CMAKE_OBJCOPY ${HEXAGON_BIN}/${CROSSDEV}objcopy) + +list2string(HEXAGON_INCLUDE_DIRS + -I${HEXAGON_TOOLS_ROOT}/target/hexagon/include + ) + +#set(DYNAMIC_LIBS -Wl,${TOOLSLIB}/pic/libstdc++.a) + +#set(MAXOPTIMIZATION -O0) + +# Base CPU flags for each of the supported architectures. +# +set(ARCHCPUFLAGS + -m${V_ARCH} + -G0 + ) + +add_definitions( + -D_PID_T -D_UID_T -D_TIMER_T + -Dnoreturn_function= + -D__EXPORT= + -Drestrict= + -D_DEBUG + -Wno-error=shadow + ) + +# optimisation flags +# +set(ARCHOPTIMIZATION + -O0 + -g + -fno-strict-aliasing + -fdata-sections + -fno-zero-initialized-in-bss + ) + +# Language-specific flags +# +set(ARCHCFLAGS + -std=gnu99 + -D__CUSTOM_FILE_IO__ + ) +set(ARCHCXXFLAGS + -fno-exceptions + -fno-rtti + -std=c++11 + -fno-threadsafe-statics + -DCONFIG_WCHAR_BUILTIN + -D__CUSTOM_FILE_IO__ + ) + +set(ARCHWARNINGS + -Wall + -Wextra + -Werror + -Wno-unused-parameter + -Wno-unused-function + -Wno-unused-variable + -Wno-gnu-array-member-paren-init + -Wno-cast-align + -Wno-missing-braces + -Wno-strict-aliasing +# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+ +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + ) + +# C-specific warnings +# +set(ARCHCWARNINGS + ${ARCHWARNINGS} + -Wstrict-prototypes + -Wnested-externs + ) + +# C++-specific warnings +# +set(ARCHWARNINGSXX + ${ARCHWARNINGS} + -Wno-missing-field-initializers + ) +exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-libgcc-file-name OUTPUT_VARIABLE LIBGCC) +exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-file-name=libm.a OUTPUT_VARIABLE LIBM) +set(EXTRA_LIBS ${EXTRA_LIBS} ${LIBM}) + +# Flags we pass to the C compiler +# +list2string(CFLAGS + ${ARCHCFLAGS} + ${ARCHCWARNINGS} + ${ARCHOPTIMIZATION} + ${ARCHCPUFLAGS} + ${ARCHINCLUDES} + ${INSTRUMENTATIONDEFINES} + ${ARCHDEFINES} + ${EXTRADEFINES} + ${EXTRACFLAGS} + ${HEXAGON_INCLUDE_DIRS} + ) + +# Flags we pass to the C++ compiler +# +list2string(CXXFLAGS + ${ARCHCXXFLAGS} + ${ARCHWARNINGSXX} + ${ARCHOPTIMIZATION} + ${ARCHCPUFLAGS} + ${ARCHXXINCLUDES} + ${INSTRUMENTATIONDEFINES} + ${ARCHDEFINES} + ${EXTRADEFINES} + ${EXTRACXXFLAGS} + ${HEXAGON_INCLUDE_DIRS} + ) + +# Flags we pass to the assembler +# +list2string(AFLAGS + ${CFLAGS} + -D__ASSEMBLY__ + ${EXTRADEFINES} + ${EXTRAAFLAGS} + ) + +# Set cmake flags +# +list2string(CMAKE_C_FLAGS + ${CMAKE_C_FLAGS} + ${CFLAGS} + ) + +set(QURT_CMAKE_C_FLAGS ${CMAKE_C_FLAGS} CACHE STRING "cflags") + +message(STATUS "CMAKE_C_FLAGS: -${CMAKE_C_FLAGS}-") + +list2string(CMAKE_CXX_FLAGS + ${CMAKE_CXX_FLAGS} + ${CXXFLAGS} + ) + +set(QURT_CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} CACHE STRING "cxxflags") + +message(STATUS "CMAKE_CXX_FLAGS: -${CMAKE_CXX_FLAGS}-") + +# Flags we pass to the linker +# +list2string(CMAKE_EXE_LINKER_FLAGS + -g + -mv5 + -mG0lib + -G0 + -fpic + -shared + -Wl,-Bsymbolic + -Wl,--wrap=malloc + -Wl,--wrap=calloc + -Wl,--wrap=free + -Wl,--wrap=realloc + -Wl,--wrap=memalign + -Wl,--wrap=__stack_chk_fail + -lc + ${EXTRALDFLAGS} + ) + +# where is the target environment +set(CMAKE_FIND_ROOT_PATH get_file_component(${C_COMPILER} PATH)) + +set(CMAKE_C_COMPILER_ID, "Clang") +set(CMAKE_CXX_COMPILER_ID, "Clang") + +# search for programs in the build host directories +set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +# for libraries and headers in the target directories +set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) +set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h index a0bc87cf0b..496e272d62 100644 --- a/src/drivers/drv_hrt.h +++ b/src/drivers/drv_hrt.h @@ -44,7 +44,7 @@ #define __STDC_FORMAT_MACROS #include -#include +#include #include __BEGIN_DECLS diff --git a/src/firmware/qurt/CMakeLists.txt b/src/firmware/qurt/CMakeLists.txt index 7f52c59e4c..3dc12c57f6 100644 --- a/src/firmware/qurt/CMakeLists.txt +++ b/src/firmware/qurt/CMakeLists.txt @@ -1,10 +1,5 @@ include_directories(${CMAKE_CURRENT_BINARY_DIR}) -set(V_ARCH v5) -set(HEXAGON_TOOLS_ROOT /opt/6.4.03) -set(TOOLSLIB - ${HEXAGON_TOOLS_ROOT}/dinkumware/lib/${V_ARCH}/G0) - px4_qurt_generate_builtin_commands( OUT ${CMAKE_BINARY_DIR}/apps.h MODULE_LIST ${module_libraries}) diff --git a/src/lib/dspal b/src/lib/dspal index 229f2f4d84..95e91546f4 160000 --- a/src/lib/dspal +++ b/src/lib/dspal @@ -1 +1 @@ -Subproject commit 229f2f4d8471564f01fe8330e5de1554a9b7aeb6 +Subproject commit 95e91546f42e6d88d34a2bb29d0f428a8706c9e4 diff --git a/src/modules/attitude_estimator_q/CMakeLists.txt b/src/modules/attitude_estimator_q/CMakeLists.txt index a727305b9a..3f89f45cdb 100644 --- a/src/modules/attitude_estimator_q/CMakeLists.txt +++ b/src/modules/attitude_estimator_q/CMakeLists.txt @@ -29,12 +29,17 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # -############################################################################ +############################################################################# +set(MODULE_CFLAGS) +if (NOT ${OS} STREQUAL "qurt") + list(APPEND MODULE_CFLAGS + -Wframe-larger-than=1400) +endif() px4_add_module( MODULE modules__attitude_estimator_q MAIN attitude_estimator_q COMPILE_FLAGS - -Wframe-larger-than=1400 + ${MODULE_CFLAGS} STACK 1200 SRCS attitude_estimator_q_main.cpp diff --git a/src/modules/commander/CMakeLists.txt b/src/modules/commander/CMakeLists.txt index a831aa9bce..64954c6d69 100644 --- a/src/modules/commander/CMakeLists.txt +++ b/src/modules/commander/CMakeLists.txt @@ -30,13 +30,18 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ +set(MODULE_CFLAGS -Os) + +if(NOT ${OS} STREQUAL "qurt") + list(APPEND MODULE_CFLAGS + -Wframe-larger-than=2200) +endif() px4_add_module( MODULE modules__commander MAIN commander STACK 5000 COMPILE_FLAGS - -Wframe-larger-than=2200 - -Os + ${MODULE_CFLAGS} SRCS commander.cpp commander_params.c diff --git a/src/modules/ekf_att_pos_estimator/CMakeLists.txt b/src/modules/ekf_att_pos_estimator/CMakeLists.txt index 9386cbf9fa..5a70282103 100644 --- a/src/modules/ekf_att_pos_estimator/CMakeLists.txt +++ b/src/modules/ekf_att_pos_estimator/CMakeLists.txt @@ -30,13 +30,16 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ + +set(MODULE_CFLAGS -Weffc++) +if(NOT ${OS} STREQUAL "qurt") + list(APPEND MODULE_CFLAGS -Wframe-larger-than=3400) +endif() + px4_add_module( MODULE modules__ekf_att_pos_estimator MAIN ekf_att_pos_estimator - COMPILE_FLAGS - -Weffc++ - -Wframe-larger-than=3400 - -O3 + COMPILE_FLAGS ${MODULE_CFLAGS} SRCS ekf_att_pos_estimator_main.cpp ekf_att_pos_estimator_params.c diff --git a/src/modules/position_estimator_inav/CMakeLists.txt b/src/modules/position_estimator_inav/CMakeLists.txt index 5ba3d7b64d..0e801603a8 100644 --- a/src/modules/position_estimator_inav/CMakeLists.txt +++ b/src/modules/position_estimator_inav/CMakeLists.txt @@ -30,12 +30,15 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ +set(MODULE_CFLAGS) +if(NOT ${OS} STREQUAL "qurt") + list(APPEND MODULE_CFLAGS -Wframe-larger-than=3800) +endif() px4_add_module( MODULE modules__position_estimator_inav MAIN position_estimator_inav STACK 1200 - COMPILE_FLAGS - -Wframe-larger-than=3800 + COMPILE_FLAGS ${MODULE_CFLAGS} SRCS position_estimator_inav_main.c diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 86df382df8..5c2ec02be0 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -366,7 +366,7 @@ private: int init_sensor_class(const struct orb_metadata *meta, int *subs, - unsigned *priorities, unsigned *errcount); + uint32_t *priorities, uint32_t *errcount); /** * Update our local parameter cache. @@ -1949,7 +1949,7 @@ Sensors::task_main_trampoline(int argc, char *argv[]) int Sensors::init_sensor_class(const struct orb_metadata *meta, int *subs, - unsigned *priorities, unsigned *errcount) + uint32_t *priorities, uint32_t *errcount) { unsigned group_count = orb_group_count(meta); diff --git a/src/platforms/posix/work_queue/hrt_thread.c b/src/platforms/posix/work_queue/hrt_thread.c index ece3a72e79..efe09ea860 100644 --- a/src/platforms/posix/work_queue/hrt_thread.c +++ b/src/platforms/posix/work_queue/hrt_thread.c @@ -40,6 +40,7 @@ #include #include +#include #include #include #include diff --git a/src/platforms/qurt/px4_layer/drv_hrt.c b/src/platforms/qurt/px4_layer/drv_hrt.c index 45be19ec8a..b5d6bd20ff 100644 --- a/src/platforms/qurt/px4_layer/drv_hrt.c +++ b/src/platforms/qurt/px4_layer/drv_hrt.c @@ -37,10 +37,12 @@ * High-resolution timer with callouts and timekeeping. */ +#include #include #include #include #include +#include #include #include diff --git a/src/systemcmds/mixer/CMakeLists.txt b/src/systemcmds/mixer/CMakeLists.txt index c49433c864..dd051b2772 100644 --- a/src/systemcmds/mixer/CMakeLists.txt +++ b/src/systemcmds/mixer/CMakeLists.txt @@ -30,13 +30,18 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ +set(MIXER_CFLAGS -Os) +if(${OS} STREQUAL "qurt") + list(APPEND MIXER_CFLAGS -Wframe-larger-than=2176) +else() + list(APPEND MIXER_CFLAGS -Wframe-larger-than=2048) +endif() + px4_add_module( MODULE systemcmds__mixer MAIN mixer STACK 4096 - COMPILE_FLAGS - -Wframe-larger-than=2048 - -Os + COMPILE_FLAGS ${MIXER_CFLAGS} SRCS mixer.cpp DEPENDS