Browse Source

Work on config only for cmake arguments.

sbg
James Goppert 10 years ago
parent
commit
07851b79c2
  1. 136
      CMakeLists.txt
  2. 17
      Makefile
  3. 369
      cmake/configs/nuttx_px4fmu-v2_default.cmake
  4. 1
      cmake/nuttx/px4_impl_nuttx.cmake
  5. 9
      src/firmware/nuttx/CMakeLists.txt

136
CMakeLists.txt

@ -95,116 +95,89 @@ @@ -95,116 +95,89 @@
#
#=============================================================================
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
project(px4 CXX C ASM)
if (NOT ${CMAKE_VERSION} VERSION_LESS 3.0.0)
cmake_policy(SET CMP0045 NEW) # error on non-existent target in get prop
cmake_policy(SET CMP0046 NEW) # no non-existent targets as dependencies
endif()
set(version_major 0)
set(version_minor 1)
set(verion_patch 2)
set(version "${version_major}.${version_minor}.${version_patch}")
set(package-contact "px4users@googlegroups.com")
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
#=============================================================================
# Validate build configuration and build
# parameters
#
if (NOT NESTED_CMAKE_CALL)
message(STATUS "IN TOP")
if (EXISTS ${CMAKE_SOURCE_DIR}/cmake/configs/${CONFIG}.cmake)
# Get the toolchain information
include(configs/${CONFIG})
else()
message(FATAL_ERROR "build config not found: ${CONFIG}.cmake")
endif()
if (NOT "${USE_TOOLCHAIN}" STREQUAL "")
set(TOOLCHAIN -DCMAKE_TOOLCHAIN_FILE=${CMAKE_SOURCE_DIR}/cmake/toolchains/${USE_TOOLCHAIN}.cmake)
endif()
string(REPLACE "_" ";" TARGET_PARAMS ${CONFIG})
list(GET TARGET_PARAMS 0 OS)
list(GET TARGET_PARAMS 1 BOARD)
list(GET TARGET_PARAMS 2 LABEL)
execute_process( COMMAND ${CMAKE_COMMAND} -E make_directory ${CONFIG} )
set(NESTED_CMAKE_CALL 1)
message(STATUS "Before")
execute_process(WORKING_DIRECTORY ${CONFIG}
COMMAND ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} -DNESTED_CMAKE_CALL=TRUE ${TOOLCHAIN} -DOS=${OS} -DBOARD=${BOARD} -DLABEL=${LABEL}
)
execute_process( WORKING_DIRECTORY ${CONFIG}
COMMAND make -s
)
message(STATUS "${CMAKE_COMMAND} VERBOSE=1 ${CMAKE_SOURCE_DIR} ${TOOLCHAIN} -DOS=${OS} -DBOARD=${BOARD} -DLABEL=${LABEL}")
return()
endif(NOT NESTED_CMAKE_CALL)
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})
set(THREADS "4" CACHE STRING
"number of threads to use for external build processes")
#=============================================================================
# cmake modules
# configuration
#
# must come before project to set toolchain
# set module path
message("OS = ${OS}")
# prefer board implementation module over os implmementation module
set(config_module "configs/config_${OS}_${BOARD}_${LABEL}")
set(config_path "${CMAKE_SOURCE_DIR}/cmake/${config_module}.cmake")
if (EXISTS ${config_path})
include(${config_module})
else()
message(FATAL_ERROR "build config not found: ${config_path}")
endif()
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
set(config_module "configs/${CONFIG}")
include(${config_module})
# require px4 module interface
set(px4_required_functions
set(px4_required_interface
px4_os_prebuild_targets
px4_os_add_flags
px4_get_config
)
foreach(cmd ${px4_required_functions})
foreach(cmd ${px4_required_interface})
if(NOT COMMAND ${cmd})
message(FATAL_ERROR "cmake/${impl_module} must implement ${cmd}")
message(FATAL_ERROR "${config_module} must implement ${cmd}")
endif()
endforeach()
set(px4_required_config
config_firmware_options
config_extra_builtin_cmds
config_module_list
)
foreach(conf ${px4_required_config})
if(NOT DEFINED ${conf})
message(FATAL_ERROR "${config_module} must define ${conf}")
endif()
endforeach()
# other modules
enable_testing()
#=============================================================================
# programs
#
find_package(PythonInterp REQUIRED)
#=============================================================================
# parameters
# project definition
#
project(px4 CXX C ASM)
if (NOT ${CMAKE_VERSION} VERSION_LESS 3.0.0)
cmake_policy(SET CMP0045 NEW) # error on non-existent target in get prop
cmake_policy(SET CMP0046 NEW) # no non-existent targets as dependencies
endif()
set(OS "posix" CACHE STRING "desired operating system")
set_property(CACHE OS PROPERTY STRINGS nuttx posix qurt)
set(version_major 0)
set(version_minor 1)
set(verion_patch 2)
set(version "${version_major}.${version_minor}.${version_patch}")
set(package-contact "px4users@googlegroups.com")
set(BOARD "sitl" CACHE STRING "target board")
set_property(CACHE BOARD PROPERTY STRINGS px4fmu-v2 sitl)
string(REPLACE "_" ";" config_args ${CONFIG})
list(GET config_args 0 OS)
list(GET config_args 1 BOARD)
list(GET config_args 2 LABEL)
set(LABEL "simple" CACHE STRING "module set label")
set_property(CACHE LABEL PROPERTY STRINGS simple default)
message(STATUS "TARGET: OS(${OS})-BOARD(${BOARD})-LABEL(${LABEL})")
set(THREADS "4" CACHE STRING
"number of threads to use for external build processes")
#=============================================================================
# cmake modules
#
enable_testing()
set(required_toolchain_variables
CMAKE_C_COMPILER_ID
)
#=============================================================================
# programs
#
find_package(PythonInterp REQUIRED)
#=============================================================================
# check required toolchain variables
#
foreach(var ${required_toolchain_variables})
set(required_variables
CMAKE_C_COMPILER_ID
)
foreach(var ${required_variables})
if (NOT ${var})
message(FATAL_ERROR "Toolchain must define ${var}")
message(FATAL_ERROR "Toolchain/config must define ${var}")
endif()
endforeach()
@ -267,9 +240,8 @@ px4_generate_messages(TARGET msg_gen @@ -267,9 +240,8 @@ px4_generate_messages(TARGET msg_gen
#=============================================================================
# subdirectories
#
px4_get_config(OUT_MODULES config_modules)
set(module_libraries)
foreach(module ${config_modules})
foreach(module ${config_module_list})
add_subdirectory(src/${module})
px4_mangle_name(${module} mangled_name)
list(APPEND module_libraries ${mangled_name})

17
Makefile

@ -59,10 +59,8 @@ ARGS := $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS)) @@ -59,10 +59,8 @@ ARGS := $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS))
# --------------------------------------------------------------------
# define a make function to describe how to build a cmake config
define cmake-build
mkdir -p $(PWD)/build_$@ && cd $(PWD)/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/$(1).cmake \
-DOS=$(2) -DBOARD=$(3) -DLABEL=$(4) && \
make -s $(ARGS)
mkdir -p $(PWD)/build_$@ && cd $(PWD)/build_$@ && cmake .. -DCONFIG=$(1)
make -C $(PWD)/build_$@ -s $(ARGS)
endef
@ -71,20 +69,19 @@ endef @@ -71,20 +69,19 @@ endef
# Do not put any spaces between function arguments.
px4fmu-v2_default:
$(call cmake-build,Toolchain-arm-none-eabi,nuttx,px4fmu-v2,default)
$(call cmake-build,nuttx_px4fmu-v2_default)
px4fmu-v2_simple:
$(call cmake-build,Toolchain-arm-none-eabi,nuttx,px4fmu-v2,default)
$(call cmake-build,nuttx_px4fmu-v2_simple)
nuttx_sim_simple:
$(call cmake-build,Toolchain-native,nuttx,sim,default)
$(call cmake-build,$@)
posix_sitl_simple:
$(call cmake-build,Toolchain-posix-clang-native,posix,sitl,simple)
$(call cmake-build,$@)
qurt_eagle_travis:
$(call cmake-build,Toolchain-hexagon,qurt,eagle,travis)
$(call cmake-build,$@)
# Other targets
# --------------------------------------------------------------------

369
cmake/configs/nuttx_px4fmu-v2_default.cmake

@ -1,203 +1,178 @@ @@ -1,203 +1,178 @@
include(nuttx/px4_impl_nuttx)
function(px4_get_config)
px4_parse_function_args(
NAME px4_set_config_modules
ONE_VALUE OUT_MODULES OUT_FW_OPTS OUT_EXTRA_CMDS
ARGN ${ARGN})
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/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
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/reboot
systemcmds/top
systemcmds/config
systemcmds/nshterm
systemcmds/mtd
systemcmds/dumpfile
systemcmds/ver
#
# General system control
#
modules/commander
modules/navigator
modules/mavlink
modules/gpio_led
#modules/uavcan # have to fix CMakeLists.txt
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/ekf_att_pos_estimator
modules/position_estimator_inav
#
# Vehicle Control
#
# modules/segway # XXX Needs GCC 4.7 fix
modules/fw_pos_control_l1
modules/fw_att_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control
#
# Logging
#
modules/sdlog2
#
# Library modules
#
modules/systemlib
modules/systemlib/mixer
modules/controllib
modules/uORB
modules/dataman
#
# Libraries
#
#lib/mathlib/CMSIS
lib/mathlib
lib/mathlib/math/filter
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/launchdetection
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
#
# PX4 flow estimator, good for indoors
#
examples/flow_position_estimator
#
# 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(CMAKE_TOOLCHAIN_FILE 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/px4io
drivers/boards/px4fmu-v2
drivers/rgbled
drivers/mpu6000
drivers/mpu9250
drivers/lsm303d
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
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
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/reboot
systemcmds/top
systemcmds/config
systemcmds/nshterm
systemcmds/mtd
systemcmds/dumpfile
systemcmds/ver
#
# General system control
#
modules/commander
modules/navigator
modules/mavlink
modules/gpio_led
#modules/uavcan # have to fix CMakeLists.txt
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/ekf_att_pos_estimator
modules/position_estimator_inav
#
# Vehicle Control
#
# modules/segway # XXX Needs GCC 4.7 fix
modules/fw_pos_control_l1
modules/fw_att_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control
#
# Logging
#
modules/sdlog2
#
# Library modules
#
modules/systemlib
modules/systemlib/mixer
modules/controllib
modules/uORB
modules/dataman
#
# Libraries
#
#lib/mathlib/CMSIS
lib/mathlib
lib/mathlib/math/filter
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/launchdetection
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
#
# PX4 flow estimator, good for indoors
#
examples/flow_position_estimator
#
# 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_firmware_options
PARAM_XML # generate param xml
)
set(firmware_options
PARAM_XML # generate param xml
)
set(extra_cmds serdis_main sercon_main)
# output
if(OUT_MODULES)
set(${OUT_MODULES} ${config_module_list} PARENT_SCOPE)
endif()
if (OUT_FW_OPTS)
set(${OUT_FW_OPTS} ${fw_opts} PARENT_SCOPE)
endif()
endfunction()
function(px4_add_extra_builtin_cmds)
px4_parse_function_args(
NAME px4_add_extra_builtin_cmds
ONE_VALUE OUT
REQUIRED OUT
ARGN ${ARGN})
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")
set(config_extra_builtin_cmds
serdis_main
sercon_main
)
set(${OUT} sercon serdis PARENT_SCOPE)
add_custom_target(sercon)
set_target_properties(sercon PROPERTIES
MAIN "sercon" STACK "2048")
endfunction()
add_custom_target(serdis)
set_target_properties(serdis PROPERTIES
MAIN "serdis" STACK "2048")

1
cmake/nuttx/px4_impl_nuttx.cmake

@ -143,7 +143,6 @@ function(px4_nuttx_generate_builtin_commands) @@ -143,7 +143,6 @@ function(px4_nuttx_generate_builtin_commands)
MULTI_VALUE MODULE_LIST
REQUIRED MODULE_LIST OUT
ARGN ${ARGN})
message(STATUS "argn: ${ARGN}")
set(builtin_apps_string)
set(builtin_apps_decl_string)
set(command_count 0)

9
src/firmware/nuttx/CMakeLists.txt

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
px4_add_extra_builtin_cmds(OUT extra_builtins)
px4_nuttx_generate_builtin_commands(
OUT builtin_commands.c
MODULE_LIST ${module_libraries} ${extra_builtins}
MODULE_LIST
${module_libraries}
${config_extra_builtins_cmds}
)
px4_nuttx_generate_romfs(OUT romfs.o
@ -27,10 +27,9 @@ target_link_libraries(firmware_nuttx @@ -27,10 +27,9 @@ target_link_libraries(firmware_nuttx
apps nuttx nosys m gcc
-Wl,--end-group)
px4_get_config(OUT_FW_OPTS fw_opts)
px4_nuttx_add_firmware(OUT ${CMAKE_CURRENT_BINARY_DIR}/fw_main.px4
EXE ${CMAKE_CURRENT_BINARY_DIR}/firmware_nuttx
${fw_opts}
${config_firmware_options}
)
px4_add_upload(OUT upload OS ${OS} BOARD ${BOARD}

Loading…
Cancel
Save