diff --git a/.gitignore b/.gitignore index 9d415d1839..1a6e278539 100644 --- a/.gitignore +++ b/.gitignore @@ -54,3 +54,4 @@ src/platforms/posix/px4_messages/ src/platforms/posix-arm/px4_messages/ src/platforms/qurt/px4_messages/ ROMFS/*/*/rc.autostart +rootfs/ diff --git a/CMakeLists.txt b/CMakeLists.txt index 9f04b1fdd6..8354de7399 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -92,6 +92,8 @@ # Included CMake Files # --------------------------------------------------------------------------- # +# * All variables in config files must have the prefix "config_". +# # * Never set global variables in an included cmake file, # you may only define functions. This excludes config and Toolchain files. # This makes it clear to the user when variables are being set or targets @@ -121,6 +123,9 @@ cmake_minimum_required(VERSION 2.8 FATAL_ERROR) # parameters # +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") file(GLOB_RECURSE configs RELATIVE cmake/configs "cmake/configs/*.cmake") set_property(CACHE CONFIG PROPERTY STRINGS ${configs}) @@ -178,8 +183,9 @@ string(REPLACE "_" ";" config_args ${CONFIG}) list(GET config_args 0 OS) list(GET config_args 1 BOARD) list(GET config_args 2 LABEL) +set(target_name "${OS}-${BOARD}-${LABEL}") -message(STATUS "OS=${OS} BOARD=${BOARD} LABEL=${LABEL}") +message(STATUS "${target_name}") #============================================================================= # programs @@ -271,6 +277,9 @@ foreach(module ${config_module_list}) endforeach() add_subdirectory(src/firmware/${OS}) +if (config_io_board) + #add_subdirectory(src/modules/px4iofirmware) +endif() #============================================================================= # generate git version diff --git a/Makefile b/Makefile index b1dd099eb6..db133aea51 100644 --- a/Makefile +++ b/Makefile @@ -92,13 +92,13 @@ qurt_eagle_travis: posix: posix_sitl_simple -sitl_quad: +sitl_quad: posix Tools/sitl_run.sh posix-configs/SITL/init/rcS -sitl_plane: +sitl_plane: posix Tools/sitl_run.sh posix-configs/SITL/init/rc.fixed_wing -sitl_ros: +sitl_ros: posix Tools/sitl_run.sh posix-configs/SITL/init/rc_iris_ros # Other targets diff --git a/cmake/common/px4_base.cmake b/cmake/common/px4_base.cmake index 482fc54aa5..022261a58d 100644 --- a/cmake/common/px4_base.cmake +++ b/cmake/common/px4_base.cmake @@ -103,7 +103,7 @@ function(px4_parse_function_args) endif() foreach(arg ${IN_REQUIRED}) if (NOT OUT_${arg}) - message(FATAL_ERROR "${IN_NAME} requires argument ${arg}, ARGN: ${IN_ARGN}") + message(FATAL_ERROR "${IN_NAME} requires argument ${arg}\nARGN: ${IN_ARGN}") endif() endforeach() foreach(arg ${IN_OPTIONS} ${IN_ONE_VALUE} ${IN_MULTI_VALUE}) @@ -593,25 +593,25 @@ function(px4_add_common_flags) ) set(added_include_dirs - src + ${CMAKE_SOURCE_DIR}/src ${CMAKE_BINARY_DIR} ${CMAKE_BINARY_DIR}/src - src/modules - src/include - src/lib - src/platforms + ${CMAKE_SOURCE_DIR}/src/modules + ${CMAKE_SOURCE_DIR}/src/include + ${CMAKE_SOURCE_DIR}/src/lib + ${CMAKE_SOURCE_DIR}/src/platforms # TODO Build/versioning was in Makefile, # do we need this, how does it work with cmake - src/drivers/boards/${BOARD} + ${CMAKE_SOURCE_DIR}/src/drivers/boards/${BOARD} ${CMAKE_BINARY_DIR} ${CMAKE_BINARY_DIR}/src/modules/px4_messages ${CMAKE_BINARY_DIR}/src/modules - mavlink/include/mavlink + ${CMAKE_SOURCE_DIR}/mavlink/include/mavlink ) if (NOT ${OS} STREQUAL "qurt") list(APPEND added_include_dirs - src/lib/eigen + ${CMAKE_SOURCE_DIR}/src/lib/eigen ) endif() diff --git a/cmake/configs/nuttx_px4fmu-v2_default.cmake b/cmake/configs/nuttx_px4fmu-v2_default.cmake index 0ea1c0d800..84885c1c59 100644 --- a/cmake/configs/nuttx_px4fmu-v2_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_default.cmake @@ -165,6 +165,18 @@ set(config_extra_builtin_cmds sercon ) +set(config_io_board + px4io-v2 + ) + +set(config_extra_libs + ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a + ) + +set(config_io_extra_libs + ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a + ) + add_custom_target(sercon) set_target_properties(sercon PROPERTIES MAIN "sercon" STACK "2048") diff --git a/cmake/configs/nuttx_px4fmu-v2_simple.cmake b/cmake/configs/nuttx_px4fmu-v2_simple.cmake index e6777cd32a..c9b054052b 100644 --- a/cmake/configs/nuttx_px4fmu-v2_simple.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_simple.cmake @@ -3,7 +3,6 @@ include(nuttx/px4_impl_nuttx) set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-arm-none-eabi.cmake) set(config_module_list - # # Board support modules # @@ -127,6 +126,18 @@ set(config_extra_builtin_cmds sercon ) +set(config_io_board + px4io-v2 + ) + +set(config_extra_libs + ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a + ) + +set(config_io_extra_libs + ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a + ) + add_custom_target(sercon) set_target_properties(sercon PROPERTIES MAIN "sercon" STACK "2048") diff --git a/cmake/configs/nuttx_sim_simple.cmake b/cmake/configs/nuttx_sim_simple.cmake index a777e915f9..c457431ad6 100644 --- a/cmake/configs/nuttx_sim_simple.cmake +++ b/cmake/configs/nuttx_sim_simple.cmake @@ -5,16 +5,16 @@ message(WARNING "this is a work in progress and doesn't build yet") set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-native.cmake) set(config_module_list - platforms/nuttx - platforms/nuttx/px4_layer + #platforms/nuttx + #platforms/nuttx/px4_layer platforms/common - drivers/led + #drivers/led drivers/device - modules/systemlib - modules/uORB - examples/px4_simple_app - lib/mathlib/math/filter - lib/conversion + #modules/systemlib + #modules/uORB + #examples/px4_simple_app + #lib/mathlib/math/filter + #lib/conversion ) set(config_firmware_options @@ -22,15 +22,4 @@ set(config_firmware_options ) set(config_extra_builtin_cmds - serdis - sercon ) - -add_custom_target(sercon) -set_target_properties(sercon PROPERTIES - MAIN "sercon" STACK "2048") - -add_custom_target(serdis) -set_target_properties(serdis PROPERTIES - MAIN "serdis" STACK "2048") - diff --git a/cmake/nuttx/px4_impl_nuttx.cmake b/cmake/nuttx/px4_impl_nuttx.cmake index 0d07dd4560..8b82ed1704 100644 --- a/cmake/nuttx/px4_impl_nuttx.cmake +++ b/cmake/nuttx/px4_impl_nuttx.cmake @@ -61,6 +61,7 @@ include(common/px4_base) # # Input: # EXE : the executable to generate the firmware from +# BOARD : the board # # Options: # PARAM_XML : toggles generation of param_xml @@ -74,9 +75,9 @@ include(common/px4_base) function(px4_nuttx_add_firmware) px4_parse_function_args( NAME px4_nuttx_add_firmware - ONE_VALUE OUT EXE + ONE_VALUE BOARD OUT EXE OPTIONS PARAM_XML - REQUIRED EXE + REQUIRED OUT EXE BOARD ARGN ${ARGN}) set(process_params ${CMAKE_SOURCE_DIR}/Tools/px_process_params.py) @@ -111,7 +112,7 @@ function(px4_nuttx_add_firmware) DEPENDS ${EXE} ) endif() - add_custom_target(build_firmware ALL DEPENDS ${OUT}) + add_custom_target(build_firmware_${BOARD} ALL DEPENDS ${OUT}) endfunction() #============================================================================= @@ -246,14 +247,14 @@ function(px4_nuttx_add_export) DEPENDS ${DEPENDS} __nuttx_copy_${CONFIG}) # extract - add_custom_command(OUTPUT nuttx_export_${BOARD}.stamp + add_custom_command(OUTPUT nuttx_export_${CONFIG}.stamp COMMAND ${RM} -rf ${nuttx_src}/nuttx-export - COMMAND ${UNZIP} ${BOARD}.export -d ${nuttx_src} - COMMAND ${TOUCH} nuttx_export_${BOARD}.stamp - DEPENDS ${DEPENDS} ${BOARD}.export) + COMMAND ${UNZIP} ${CONFIG}.export -d ${nuttx_src} + COMMAND ${TOUCH} nuttx_export_${CONFIG}.stamp + DEPENDS ${DEPENDS} ${CONFIG}.export) add_custom_target(${OUT} - DEPENDS nuttx_export_${BOARD}.stamp) + DEPENDS nuttx_export_${CONFIG}.stamp) endfunction() @@ -406,17 +407,24 @@ function(px4_os_add_flags) set(added_exe_linker_flags) # none currently - if ("${BOARD}" STREQUAL "px4fmu-v2") - set(arm_build_flags + set(cpu_flags) + if (${BOARD} STREQUAL "px4fmu-v2") + set(cpu_flags -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard ) - list(APPEND c_flags ${arm_build_flags}) - list(APPEND cxx_flags ${arm_build_flags}) + elseif (${BOARD} STREQUAL "px4io-v2") + set(cpu_flags + -mcpu=cortex-m3 + -mthumb + -march=armv7-m + ) endif() + list(APPEND c_flags ${cpu_flags}) + list(APPEND cxx_flags ${cpu_flags}) # output foreach(var ${inout_vars}) @@ -455,11 +463,11 @@ function(px4_os_prebuild_targets) ONE_VALUE OUT BOARD THREADS REQUIRED OUT BOARD ARGN ${ARGN}) - px4_nuttx_add_export(OUT nuttx_export + px4_nuttx_add_export(OUT nuttx_export_${BOARD} CONFIG ${BOARD} THREADS ${THREADS} DEPENDS git_nuttx) - add_custom_target(${OUT} DEPENDS nuttx_export) + add_custom_target(${OUT} DEPENDS nuttx_export_${BOARD}) endfunction() # vim: set noet fenc=utf-8 ff=unix nowrap: diff --git a/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake b/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake index 2db5cf82b9..61d63f8677 100644 --- a/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake +++ b/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake @@ -46,7 +46,7 @@ foreach(tool objcopy nm ld) endforeach() # os tools -foreach(tool echo patch grep rm mkdir nm genromfs awk cp touch make unzip) +foreach(tool echo patch grep rm mkdir nm genromfs cp touch make unzip) string(TOUPPER ${tool} TOOL) find_program(${TOOL} ${tool}) if(NOT ${TOOL}) diff --git a/cmake/toolchains/Toolchain-arm-none-eabi.cmake b/cmake/toolchains/Toolchain-arm-none-eabi.cmake index 5fab42f3c2..80da3ad1a2 100644 --- a/cmake/toolchains/Toolchain-arm-none-eabi.cmake +++ b/cmake/toolchains/Toolchain-arm-none-eabi.cmake @@ -46,7 +46,7 @@ foreach(tool objcopy nm ld gdb) endforeach() # os tools -foreach(tool echo patch grep rm mkdir nm genromfs awk cp touch make unzip) +foreach(tool echo patch grep rm mkdir nm genromfs cp touch make unzip) string(TOUPPER ${tool} TOOL) find_program(${TOOL} ${tool}) if(NOT ${TOOL}) diff --git a/cmake/toolchains/Toolchain-native.cmake b/cmake/toolchains/Toolchain-native.cmake index 0f9ad12f14..888c73a6d8 100644 --- a/cmake/toolchains/Toolchain-native.cmake +++ b/cmake/toolchains/Toolchain-native.cmake @@ -8,7 +8,7 @@ foreach(tool nm ld) endforeach() # os tools -foreach(tool echo patch grep rm mkdir nm genromfs awk cp touch make unzip) +foreach(tool echo patch grep rm mkdir nm genromfs cp touch make unzip) string(TOUPPER ${tool} TOOL) find_program(${TOOL} ${tool}) if(NOT ${TOOL}) diff --git a/src/drivers/ms5611/CMakeLists.txt b/src/drivers/ms5611/CMakeLists.txt index 8afca6ade0..7359bd9507 100644 --- a/src/drivers/ms5611/CMakeLists.txt +++ b/src/drivers/ms5611/CMakeLists.txt @@ -30,15 +30,29 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ +set(srcs + ms5611_spi.cpp + ms5611_i2c.cpp + ) + +if(${OS} STREQUAL "nuttx") + list(APPEND srcs + ms5611_nuttx.cpp + ) +else() + list(APPEND srcs + ms5611_posix.cpp + ms5611_sim.cpp + ) + +endif() + px4_add_module( MODULE drivers__ms5611 MAIN ms5611 COMPILE_FLAGS -Os - SRCS - ms5611_nuttx.cpp - ms5611_spi.cpp - ms5611_i2c.cpp + SRCS ${srcs} DEPENDS platforms__common ) diff --git a/src/firmware/nuttx/CMakeLists.txt b/src/firmware/nuttx/CMakeLists.txt index b069d8849b..bb9aac3113 100644 --- a/src/firmware/nuttx/CMakeLists.txt +++ b/src/firmware/nuttx/CMakeLists.txt @@ -13,44 +13,57 @@ add_executable(firmware_nuttx builtin_commands.c romfs.o) set(nuttx_export_dir ${CMAKE_BINARY_DIR}/${BOARD}/NuttX/nuttx-export) -set(main_link_flags - "-T${nuttx_export_dir}/build/ld.script" - "-Wl,-Map=${CMAKE_BINARY_DIR}/main.map" + +set(link_libs + apps nuttx m gcc ) -px4_join(OUT main_link_flags LIST ${main_link_flags} GLUE " ") -set_target_properties(firmware_nuttx PROPERTIES LINK_FLAGS ${main_link_flags}) -set(cmsis_lib ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a) +if(NOT ${BOARD} STREQUAL "sim") + list(APPEND link_libs nosys) + set(main_link_flags + "-T${nuttx_export_dir}/build/ld.script" + "-Wl,-Map=${CMAKE_BINARY_DIR}/${BOARD}/main.map" + ) + px4_join(OUT main_link_flags LIST ${main_link_flags} GLUE " ") + set_target_properties(firmware_nuttx PROPERTIES LINK_FLAGS ${main_link_flags}) +endif() + +set(fw_file ${CMAKE_CURRENT_BINARY_DIR}/${target_name}.px4) target_link_libraries(firmware_nuttx -Wl,--start-group ${module_libraries} - ${cmsis_lib} - apps nuttx nosys m gcc + ${config_extra_libs} + ${link_libs} -Wl,--end-group) -set(fw_file ${CMAKE_CURRENT_BINARY_DIR}/${OS}-${BOARD}-${LABEL}.px4) - add_custom_target(check_weak - COMMAND ${NM} firmware_nuttx | grep " w " + COMMAND ${NM} firmware_nuttx | ${GREP} " w " | cat DEPENDS firmware_nuttx + VERBATIM ) -px4_nuttx_add_firmware(OUT ${fw_file} - EXE firmware_nuttx - ${config_firmware_options} - ) +if(NOT ${BOARD} STREQUAL "sim") + set(fw_file + ${CMAKE_CURRENT_BINARY_DIR}/${OS}-${BOARD}-${LABEL}.px4) -configure_file(gdbinit.in .gdbinit) + px4_nuttx_add_firmware(OUT ${fw_file} + BOARD ${BOARD} + EXE ${CMAKE_CURRENT_BINARY_DIR}/firmware_nuttx + ${config_firmware_options} + ) -add_custom_target(debug - COMMAND ${GDB} ${CMAKE_CURRENT_BINARY_DIR}/firmware_nuttx - DEPENDS firmware_nuttx - ${CMAKE_CURRENT_BINARY_DIR}/.gdbinit - ) + configure_file(gdbinit.in .gdbinit) + + add_custom_target(debug + COMMAND ${GDB} ${CMAKE_CURRENT_BINARY_DIR}/firmware_nuttx + DEPENDS firmware_nuttx + ${CMAKE_CURRENT_BINARY_DIR}/.gdbinit + ) -px4_add_upload(OUT upload OS ${OS} BOARD ${BOARD} - BUNDLE ${fw_file}) + px4_add_upload(OUT upload OS ${OS} BOARD ${BOARD} + BUNDLE ${fw_file}) +endif() install(FILES ${fw_file} DESTINATION .) diff --git a/src/modules/px4iofirmware/CMakeLists.txt b/src/modules/px4iofirmware/CMakeLists.txt index 0680fde22c..a8c5d681ab 100644 --- a/src/modules/px4iofirmware/CMakeLists.txt +++ b/src/modules/px4iofirmware/CMakeLists.txt @@ -30,27 +30,108 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ -px4_add_module( - MODULE modules__px4iofirmware - SRCS - adc.c - controls.c - dsm.c - px4io.c - registers.c - safety.c - sbus.c - ../systemlib/up_cxxinitialize.c - ../systemlib/perf_counter.c - mixer.cpp - ../systemlib/mixer/mixer.cpp - ../systemlib/mixer/mixer_group.cpp - ../systemlib/mixer/mixer_multirotor.cpp - ../systemlib/mixer/mixer_simple.cpp - ../systemlib/pwm_limit/pwm_limit.c - ../../lib/rc/st24.c - ../../lib/rc/sumd.c - DEPENDS - platforms__common + +# kill all flags above us, this is a different board (io) +set_directory_properties(PROPERTIES + INCLUDE_DIRECTORIES "" + LINK_DIRECTORIES "" + COMPILE_DEFINITIONS "" ) +set(c_flags) +set(exe_linker_flags) +set(cxx_flags) +set(include_dirs) +set(link_dirs) +set(definitions) + +px4_os_prebuild_targets(OUT io_prebuild_targets + BOARD ${config_io_board} + THREADS ${THREADS}) + +px4_os_add_flags( + BOARD ${config_io_board} + C_FLAGS c_flags + CXX_FLAGS cxx_flags + EXE_LINKER_FLAGS exe_linker_flags + INCLUDE_DIRS include_dirs + LINK_DIRS link_dirs + DEFINITIONS definitions) + +px4_join(OUT CMAKE_EXE_LINKER_FLAGS LIST "${exe_linker_flags}" GLUE " ") +px4_join(OUT CMAKE_C_FLAGS LIST "${c_flags}" GLUE " ") +px4_join(OUT CMAKE_CXX_FLAGS LIST "${cxx_flags}" GLUE " ") + +include_directories( + ${include_dirs} + ${CMAKE_BINARY_DIR}/src/modules/systemlib/mixer + ) +link_directories(${link_dirs}) +add_definitions(${definitions}) + +set(srcs + adc.c + controls.c + dsm.c + px4io.c + registers.c + safety.c + sbus.c + ../systemlib/up_cxxinitialize.c + ../systemlib/perf_counter.c + mixer.cpp + ../systemlib/mixer/mixer.cpp + ../systemlib/mixer/mixer_group.cpp + ../systemlib/mixer/mixer_multirotor.cpp + ../systemlib/mixer/mixer_simple.cpp + ../systemlib/pwm_limit/pwm_limit.c + ../../lib/rc/st24.c + ../../lib/rc/sumd.c + ../../drivers/stm32/drv_hrt.c + ../../drivers/stm32/drv_pwm_servo.c + ../../drivers/boards/${config_io_board}/px4iov2_init.c + ../../drivers/boards/${config_io_board}/px4iov2_pwm_servo.c + ) + +if(${config_io_board} STREQUAL "px4io-v1") + list(APPEND srcs + i2c.c + ) +elseif(${config_io_board} STREQUAL "px4io-v2") + list(APPEND srcs + serial.c + ../systemlib/hx_stream.c + ) +endif() + +add_executable(firmware_io_nuttx + ${srcs}) + +add_dependencies(firmware_io_nuttx + nuttx_export_${config_io_board} + msg_gen + io_prebuild_targets + ) + +set(nuttx_export_dir ${CMAKE_BINARY_DIR}/${config_io_board}/NuttX/nuttx-export) +set(main_link_flags + "-T${nuttx_export_dir}/build/ld.script" + "-Wl,-Map=${CMAKE_BINARY_DIR}/${config_io_board}/main.map" + ) +px4_join(OUT main_link_flags LIST ${main_link_flags} GLUE " ") +set_target_properties(firmware_io_nuttx PROPERTIES LINK_FLAGS ${main_link_flags}) + +set(io_fw_file ${CMAKE_CURRENT_BINARY_DIR}/${config_io_board}.px4) + +target_link_libraries(firmware_io_nuttx + -Wl,--start-group + apps nuttx nosys m gcc + ${config_io_extra_libs} + -Wl,--end-group) + +px4_nuttx_add_firmware(OUT ${io_fw_file} + BOARD ${config_io_board} + EXE ${CMAKE_CURRENT_BINARY_DIR}/firmware_io_nuttx + ${config_firmware_options} + ) + # vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/systemcmds/tests/CMakeLists.txt b/src/systemcmds/tests/CMakeLists.txt index c58048433d..41af1c0417 100644 --- a/src/systemcmds/tests/CMakeLists.txt +++ b/src/systemcmds/tests/CMakeLists.txt @@ -30,6 +30,43 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ + +set(srcs + test_adc.c + test_bson.c + test_float.c + test_gpio.c + test_hott_telemetry.c + test_hrt.c + test_int.c + test_jig_voltages.c + test_led.c + test_sensors.c + test_servo.c + test_sleep.c + test_uart_baudchange.c + test_uart_console.c + test_uart_loopback.c + test_uart_send.c + test_mixer.cpp + test_mathlib.cpp + test_file.c + test_file2.c + tests_main.c + test_param.c + test_ppm_loopback.c + test_rc.c + test_conv.cpp + test_mount.c + test_eigen.cpp + ) + +if(${OS} STREQUAL "nuttx") + list(APPEND srcs + test_time.c + ) +endif() + px4_add_module( MODULE systemcmds__tests MAIN tests @@ -37,34 +74,7 @@ px4_add_module( COMPILE_FLAGS -Wframe-larger-than=6000 -O0 - SRCS - test_adc.c - test_bson.c - test_float.c - test_gpio.c - test_hott_telemetry.c - test_hrt.c - test_int.c - test_jig_voltages.c - test_led.c - test_sensors.c - test_servo.c - test_sleep.c - test_uart_baudchange.c - test_uart_console.c - test_uart_loopback.c - test_uart_send.c - test_mixer.cpp - test_mathlib.cpp - test_file.c - test_file2.c - tests_main.c - test_param.c - test_ppm_loopback.c - test_rc.c - test_conv.cpp - test_mount.c - test_eigen.cpp + SRCS ${srcs} DEPENDS platforms__common )