waf: px4: add initial implementation

The initial implementation defines only the pre-build task generators.
This commit is contained in:
Gustavo Jose de Sousa 2016-02-26 22:45:28 +00:00 committed by Lucas De Marchi
parent 4613b68efb
commit 658bead862
5 changed files with 199 additions and 0 deletions

62
Tools/ardupilotwaf/px4.py Normal file
View File

@ -0,0 +1,62 @@
#!/usr/bin/env python
# encoding: utf-8
"""
Waf tool for PX4 build
"""
import os
def configure(cfg):
cfg.load('cmake')
env = cfg.env
def srcpath(path):
return cfg.srcnode.make_node(path).abspath()
env.PX4_CMAKE_VARS = dict(
CONFIG='nuttx_px4fmu-v%s_apm' % env.get_flat('PX4_VERSION'),
CMAKE_MODULE_PATH=srcpath('Tools/ardupilotwaf/px4/cmake'),
UAVCAN_LIBUAVCAN_PATH=srcpath('modules/uavcan'),
NUTTX_SRC=srcpath('modules/PX4NuttX'),
EXTRA_CXX_FLAGS=' '.join((
# NOTE: these "-Wno-error=*" flags should be removed as we update
# the submodule
'-Wno-error=double-promotion',
'-Wno-error=reorder',
# NOTE: *Temporarily* using this definition so that both
# PX4Firmware build systems (cmake and legacy make-based) can live
# together
'-DCMAKE_BUILD',
'-I%s' % bldpath('libraries/GCS_MAVLink'),
'-Wl,--gc-sections',
)),
EXTRA_C_FLAGS=' '.join((
# NOTE: *Temporarily* using this definition so that both
# PX4Firmware build systems (cmake and legacy make-based) can live
# together
'-DCMAKE_BUILD',
)),
)
def build(bld):
version = bld.env.get_flat('PX4_VERSION')
px4 = bld(
features='cmake_configure',
name='px4',
cmake_src=bld.srcnode.find_dir('modules/PX4Firmware'),
cmake_vars=bld.env.PX4_CMAKE_VARS,
group='dynamic_sources',
)
px4.cmake_build(
'msg_gen',
group='dynamic_sources',
cmake_output_patterns='src/modules/uORB/topics/*.h',
)
px4.cmake_build(
'prebuild_targets',
group='dynamic_sources',
cmake_output_patterns='px4fmu-v%s/NuttX/nuttx-export/**/*.h' % version,
)

View File

@ -0,0 +1,88 @@
include(nuttx/px4_impl_nuttx)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
set(config_module_list
platforms/common
platforms/nuttx
platforms/nuttx/px4_layer
modules/param
#
# Board support modules
#
drivers/device
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/led
drivers/px4fmu
drivers/rgbled
drivers/mpu6000
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/ll40ls
drivers/trone
drivers/airspeed
drivers/ets_airspeed
drivers/meas_airspeed
drivers/mkblctrl
drivers/batt_smbus
drivers/irlock
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/perf
systemcmds/pwm
systemcmds/reboot
systemcmds/top
systemcmds/nshterm
systemcmds/mtd
systemcmds/ver
systemcmds/reflect
systemcmds/motor_test
systemcmds/usb_connected
#
# Library modules
#
modules/systemlib
modules/systemlib/mixer
modules/uORB
lib/mathlib/math/filter
lib/conversion
)
set(config_extra_builtin_cmds
serdis
sercon
ArduPilot
)
set(config_extra_libs
${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a
${APM_PROGRAM_LIB}
)
set(config_uavcan_num_ifaces 2)
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"
)
add_custom_target(ArduPilot)
set_target_properties(ArduPilot PROPERTIES
MAIN "ArduPilot"
STACK "4096"
)

View File

@ -0,0 +1,12 @@
include(configs/nuttx_px4fmu-common_apm)
list(APPEND config_module_list
drivers/boards/px4fmu-v1
drivers/px4io
drivers/px4flow
)
set(config_io_board
px4io-v1
)

View File

@ -0,0 +1,23 @@
include(configs/nuttx_px4fmu-common_apm)
list(APPEND config_module_list
drivers/lsm303d
drivers/l3gd20
drivers/mpu9250
drivers/boards/px4fmu-v2
drivers/pwm_input
modules/uavcan
lib/mathlib
drivers/px4io
drivers/px4flow
drivers/oreoled
)
list(APPEND config_extra_libs
uavcan
uavcan_stm32_driver
)
set(config_io_board
px4io-v2
)

View File

@ -0,0 +1,14 @@
include(configs/nuttx_px4fmu-common_apm)
list(APPEND config_module_list
drivers/mpu9250
drivers/boards/px4fmu-v4
drivers/pwm_input
modules/uavcan
lib/mathlib
)
list(APPEND config_extra_libs
uavcan
uavcan_stm32_driver
)