Browse Source

move cmake/${OS} to platforms

sbg
Daniel Agar 7 years ago
parent
commit
678e2c415d
  1. 1
      CMakeLists.txt
  2. 1
      cmake/configs/nuttx_aerocore2_default.cmake
  3. 1
      cmake/configs/nuttx_aerofc-v1_default.cmake
  4. 1
      cmake/configs/nuttx_auav-x21_default.cmake
  5. 1
      cmake/configs/nuttx_crazyflie_default.cmake
  6. 1
      cmake/configs/nuttx_esc35-v1_default.cmake
  7. 1
      cmake/configs/nuttx_mindpx-v2_default.cmake
  8. 1
      cmake/configs/nuttx_nxphlite-v3_default.cmake
  9. 1
      cmake/configs/nuttx_px4-same70xplained-v1_default.cmake
  10. 1
      cmake/configs/nuttx_px4-stm32f4discovery_default.cmake
  11. 1
      cmake/configs/nuttx_px4cannode-v1_default.cmake
  12. 1
      cmake/configs/nuttx_px4esc-v1_default.cmake
  13. 1
      cmake/configs/nuttx_px4fmu-v2_default.cmake
  14. 1
      cmake/configs/nuttx_px4fmu-v2_test.cmake
  15. 1
      cmake/configs/nuttx_px4fmu-v3_default.cmake
  16. 1
      cmake/configs/nuttx_px4fmu-v4_default.cmake
  17. 1
      cmake/configs/nuttx_px4fmu-v4pro_default.cmake
  18. 1
      cmake/configs/nuttx_px4fmu-v5_default.cmake
  19. 1
      cmake/configs/nuttx_px4io-v2_default.cmake
  20. 1
      cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake
  21. 1
      cmake/configs/nuttx_s2740vc-v1_default.cmake
  22. 1
      cmake/configs/nuttx_tap-v1_default.cmake
  23. 1
      cmake/configs/posix_bebop_default.cmake
  24. 1
      cmake/configs/posix_eagle_hil.cmake
  25. 1
      cmake/configs/posix_eagle_muorb.cmake
  26. 1
      cmake/configs/posix_ocpoc_cross.cmake
  27. 1
      cmake/configs/posix_ocpoc_ubuntu.cmake
  28. 1
      cmake/configs/posix_rpi_common.cmake
  29. 1
      cmake/configs/posix_sdflight_default.cmake
  30. 1
      cmake/configs/posix_sdflight_legacy.cmake
  31. 1
      cmake/configs/posix_sitl_default.cmake
  32. 1
      cmake/configs/posix_sitl_replay.cmake
  33. 1
      cmake/configs/qurt_eagle_hello.cmake
  34. 1
      cmake/configs/qurt_eagle_hil.cmake
  35. 1
      cmake/configs/qurt_eagle_muorb.cmake
  36. 1
      cmake/configs/qurt_eagle_test.cmake
  37. 1
      cmake/configs/qurt_eagle_travis.cmake
  38. 1
      cmake/configs/qurt_sdflight_default.cmake
  39. 1
      cmake/configs/qurt_sdflight_legacy.cmake
  40. 47
      cmake/posix/ld.script
  41. 37
      cmake/qurt/qurt_eigen.patch
  42. 47
      cmake/qurt/qurt_funcs.cmake
  43. 0
      platforms/nuttx/cmake/px4_impl_os.cmake
  44. 0
      platforms/posix/cmake/px4_impl_os.cmake
  45. 2
      platforms/qurt/cmake/px4_impl_os.cmake

1
CMakeLists.txt

@ -155,6 +155,7 @@ if (NOT EXTERNAL_MODULES_LOCATION STREQUAL "") @@ -155,6 +155,7 @@ if (NOT EXTERNAL_MODULES_LOCATION STREQUAL "")
get_filename_component(EXTERNAL_MODULES_LOCATION "${EXTERNAL_MODULES_LOCATION}" ABSOLUTE)
endif()
include(platforms/${OS}/cmake/px4_impl_os.cmake)
set(config_module "configs/${CONFIG}")
include(${config_module})

1
cmake/configs/nuttx_aerocore2_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_aerofc-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_auav-x21_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)

1
cmake/configs/nuttx_crazyflie_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_esc35-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
add_definitions(
-DFLASH_BASED_PARAMS

1
cmake/configs/nuttx_mindpx-v2_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_nxphlite-v3_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_px4-same70xplained-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_px4-stm32f4discovery_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_px4cannode-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
add_definitions(
-DPARAM_NO_ORB

1
cmake/configs/nuttx_px4esc-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
add_definitions(
-DFLASH_BASED_PARAMS

1
cmake/configs/nuttx_px4fmu-v2_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)
#set(config_uavcan_num_ifaces 2)

1
cmake/configs/nuttx_px4fmu-v2_test.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_test)

1
cmake/configs/nuttx_px4fmu-v3_default.cmake

@ -5,7 +5,6 @@ set(FW_NAME nuttx_px4fmu-v3_default.elf CACHE string "" FORCE) @@ -5,7 +5,6 @@ set(FW_NAME nuttx_px4fmu-v3_default.elf CACHE string "" FORCE)
set(FW_PROTOTYPE px4fmu-v3 CACHE string "" FORCE)
set(LD_SCRIPT ld_full.script CACHE string "" FORCE)
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)
set(config_uavcan_num_ifaces 2)

1
cmake/configs/nuttx_px4fmu-v4_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_px4fmu-v4pro_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)

1
cmake/configs/nuttx_px4fmu-v5_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_px4io-v2_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m3 CONFIG nsh)

1
cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)

1
cmake/configs/nuttx_s2740vc-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
add_definitions(
-DPARAM_NO_ORB

1
cmake/configs/nuttx_tap-v1_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT tap_common)

1
cmake/configs/posix_bebop_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake)

1
cmake/configs/posix_eagle_hil.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(posix/px4_impl_posix)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PX4_SOURCE_DIR}/cmake/cmake_hexagon")

1
cmake/configs/posix_eagle_muorb.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-arm-linux-gnueabihf.cmake)

1
cmake/configs/posix_ocpoc_cross.cmake

@ -6,7 +6,6 @@ set(CMAKE_PROGRAM_PATH @@ -6,7 +6,6 @@ set(CMAKE_PROGRAM_PATH
${CMAKE_PROGRAM_PATH}
)
include(posix/px4_impl_posix)
add_definitions(
-D__PX4_POSIX_OCPOC

1
cmake/configs/posix_ocpoc_ubuntu.cmake

@ -5,7 +5,6 @@ set(CMAKE_PROGRAM_PATH @@ -5,7 +5,6 @@ set(CMAKE_PROGRAM_PATH
${CMAKE_PROGRAM_PATH}
)
include(posix/px4_impl_posix)
add_definitions(
-D__PX4_POSIX_OCPOC

1
cmake/configs/posix_rpi_common.cmake

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
# 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.

1
cmake/configs/posix_sdflight_default.cmake

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
include(common/px4_git)
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "cmake/cmake_hexagon")
include(posix/px4_impl_posix)
# Get $QC_SOC_TARGET from environment if existing.
if (DEFINED ENV{QC_SOC_TARGET})

1
cmake/configs/posix_sdflight_legacy.cmake

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
include(common/px4_git)
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "cmake/cmake_hexagon")
include(posix/px4_impl_posix)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PX4_SOURCE_DIR}/cmake/cmake_hexagon")

1
cmake/configs/posix_sitl_default.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)

1
cmake/configs/posix_sitl_replay.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)

1
cmake/configs/qurt_eagle_hello.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

1
cmake/configs/qurt_eagle_hil.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

1
cmake/configs/qurt_eagle_muorb.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

1
cmake/configs/qurt_eagle_test.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

1
cmake/configs/qurt_eagle_travis.cmake

@ -1,4 +1,3 @@ @@ -1,4 +1,3 @@
include(qurt/px4_impl_qurt)
set(CONFIG_SHMEM "1")

1
cmake/configs/qurt_sdflight_default.cmake

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
include(common/px4_git)
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "cmake/cmake_hexagon")
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

1
cmake/configs/qurt_sdflight_legacy.cmake

@ -1,7 +1,6 @@ @@ -1,7 +1,6 @@
include(common/px4_git)
px4_add_git_submodule(TARGET git_cmake_hexagon PATH "cmake/cmake_hexagon")
include(qurt/px4_impl_qurt)
if ("$ENV{HEXAGON_SDK_ROOT}" STREQUAL "")
message(FATAL_ERROR "Enviroment variable HEXAGON_SDK_ROOT must be set")

47
cmake/posix/ld.script

@ -1,47 +0,0 @@ @@ -1,47 +0,0 @@
/****************************************************************************
* ld.script
*
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
* Author: Mark Charlebois <charlebm@gmail.com>
*
* 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.
*
****************************************************************************/
SECTIONS
{
/*
* Construction data for parameters.
*/
__param : ALIGN(8) {
__param_start = .;
KEEP(*(__param*))
__param_end = .;
}
}
INSERT AFTER .rodata;

37
cmake/qurt/qurt_eigen.patch

@ -1,37 +0,0 @@ @@ -1,37 +0,0 @@
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
+/// \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
// 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

47
cmake/qurt/qurt_funcs.cmake

@ -1,47 +0,0 @@ @@ -1,47 +0,0 @@
############################################################################
#
# Copyright (c) 2015 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
# 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.
#
############################################################################
#=============================================================================
# FILE: posix/px4_target_impl.cmake
#
# Each PX4 target OS must implement the cmake/${OS}/px4_target_impl.cmake
# rules for their target that implement the following macros:
#
# px4_target_set_flags
# px4_target_validate_config
# px4_target_firmware
# px4_target_rules
# px4_target_testing
#
# The macros are called from the top level CMakeLists.txt
#

0
cmake/nuttx/px4_impl_nuttx.cmake → platforms/nuttx/cmake/px4_impl_os.cmake

0
cmake/posix/px4_impl_posix.cmake → platforms/posix/cmake/px4_impl_os.cmake

2
cmake/qurt/px4_impl_qurt.cmake → platforms/qurt/cmake/px4_impl_os.cmake

@ -85,7 +85,7 @@ function(px4_qurt_generate_builtin_commands) @@ -85,7 +85,7 @@ function(px4_qurt_generate_builtin_commands)
set(builtin_apps_decl_string)
set(command_count 0)
foreach(module ${MODULE_LIST})
foreach(property MAIN STACK_MAIN PRIORITY)
foreach(property MAIN STACK_MAIN PRIORITY)
get_target_property(${property} ${module} ${property})
endforeach()
if (MAIN)
Loading…
Cancel
Save