mirror of https://github.com/ArduPilot/ardupilot
waf: add waf support
This commit is contained in:
parent
b9650696b7
commit
6e7b73610d
|
@ -29,6 +29,8 @@
|
||||||
.settings/
|
.settings/
|
||||||
.autotools
|
.autotools
|
||||||
.vagrant
|
.vagrant
|
||||||
|
/.lock-waf*
|
||||||
|
/.waf*
|
||||||
/tmp/*
|
/tmp/*
|
||||||
/Tools/ArdupilotMegaPlanner/3DRRadio/bin
|
/Tools/ArdupilotMegaPlanner/3DRRadio/bin
|
||||||
/Tools/ArdupilotMegaPlanner/3DRRadio/obj
|
/Tools/ArdupilotMegaPlanner/3DRRadio/obj
|
||||||
|
|
|
@ -0,0 +1,31 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
vehicle = bld.path.name
|
||||||
|
ardupilotwaf.vehicle_stlib(
|
||||||
|
bld,
|
||||||
|
name=vehicle + '_libs',
|
||||||
|
vehicle=vehicle,
|
||||||
|
libraries=ardupilotwaf.COMMON_VEHICLE_DEPENDENT_LIBRARIES + [
|
||||||
|
'APM_Control',
|
||||||
|
'AP_Camera',
|
||||||
|
'AP_Frsky_Telem',
|
||||||
|
'AP_L1_Control',
|
||||||
|
'AP_Menu',
|
||||||
|
'AP_Mount',
|
||||||
|
'AP_Navigation',
|
||||||
|
'AP_RCMapper',
|
||||||
|
'AP_RSSI',
|
||||||
|
'AP_Relay',
|
||||||
|
'AP_ServoRelayEvents',
|
||||||
|
'PID',
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use=vehicle + '_libs',
|
||||||
|
)
|
|
@ -0,0 +1,20 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
vehicle = bld.path.name
|
||||||
|
ardupilotwaf.vehicle_stlib(
|
||||||
|
bld,
|
||||||
|
name=vehicle + '_libs',
|
||||||
|
vehicle=vehicle,
|
||||||
|
libraries=ardupilotwaf.COMMON_VEHICLE_DEPENDENT_LIBRARIES + [
|
||||||
|
'PID',
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use=vehicle + '_libs',
|
||||||
|
)
|
|
@ -0,0 +1,41 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
vehicle = bld.path.name
|
||||||
|
ardupilotwaf.vehicle_stlib(
|
||||||
|
bld,
|
||||||
|
name=vehicle + '_libs',
|
||||||
|
vehicle=vehicle,
|
||||||
|
libraries=ardupilotwaf.COMMON_VEHICLE_DEPENDENT_LIBRARIES + [
|
||||||
|
'AC_AttitudeControl',
|
||||||
|
'AC_Fence',
|
||||||
|
'AC_PID',
|
||||||
|
'AC_PrecLand',
|
||||||
|
'AC_Sprayer',
|
||||||
|
'AC_WPNav',
|
||||||
|
'AP_Camera',
|
||||||
|
'AP_Curve',
|
||||||
|
'AP_EPM',
|
||||||
|
'AP_Frsky_Telem',
|
||||||
|
'AP_IRLock',
|
||||||
|
'AP_InertialNav',
|
||||||
|
'AP_LandingGear',
|
||||||
|
'AP_Menu',
|
||||||
|
'AP_Motors',
|
||||||
|
'AP_Mount',
|
||||||
|
'AP_Parachute',
|
||||||
|
'AP_RCMapper',
|
||||||
|
'AP_RPM',
|
||||||
|
'AP_RSSI',
|
||||||
|
'AP_Relay',
|
||||||
|
'AP_ServoRelayEvents',
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use=vehicle + '_libs',
|
||||||
|
)
|
|
@ -0,0 +1,35 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
vehicle = bld.path.name
|
||||||
|
ardupilotwaf.vehicle_stlib(
|
||||||
|
bld,
|
||||||
|
name=vehicle + '_libs',
|
||||||
|
vehicle=vehicle,
|
||||||
|
libraries=ardupilotwaf.COMMON_VEHICLE_DEPENDENT_LIBRARIES + [
|
||||||
|
'APM_Control',
|
||||||
|
'APM_OBC',
|
||||||
|
'AP_Arming',
|
||||||
|
'AP_Camera',
|
||||||
|
'AP_Frsky_Telem',
|
||||||
|
'AP_L1_Control',
|
||||||
|
'AP_Menu',
|
||||||
|
'AP_Mount',
|
||||||
|
'AP_Navigation',
|
||||||
|
'AP_RCMapper',
|
||||||
|
'AP_RPM',
|
||||||
|
'AP_RSSI',
|
||||||
|
'AP_Relay',
|
||||||
|
'AP_ServoRelayEvents',
|
||||||
|
'AP_SpdHgtControl',
|
||||||
|
'AP_TECS',
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use=vehicle + '_libs',
|
||||||
|
)
|
|
@ -0,0 +1,58 @@
|
||||||
|
To keep access to waf convenient, use the following alias from the
|
||||||
|
root ArduPilot directory
|
||||||
|
|
||||||
|
alias waf="$PWD/waf"
|
||||||
|
|
||||||
|
that way waf can be called from subdirectories to trigger partial
|
||||||
|
builds.
|
||||||
|
|
||||||
|
Differently from the make-based build, with waf there's a configure step
|
||||||
|
to choose the board to be used
|
||||||
|
|
||||||
|
# Configure the Linux board.
|
||||||
|
waf configure --board=linux
|
||||||
|
|
||||||
|
by default the board used is 'sitl'. This must be called from the root
|
||||||
|
ardupilot directory. Other commands may be issued from anywhere in the
|
||||||
|
tree.
|
||||||
|
|
||||||
|
To build, use the 'waf build' command. This is the default command, so
|
||||||
|
calling just 'waf' is enough
|
||||||
|
|
||||||
|
# From the root ardupilot directory, build everything.
|
||||||
|
waf
|
||||||
|
|
||||||
|
# Waf also accepts '-j' option to parallelize the build.
|
||||||
|
waf -j8
|
||||||
|
|
||||||
|
In subdirectories of vehicles, examples and tools (they contain a
|
||||||
|
wscript file), it's possible to trigger a build of just that program
|
||||||
|
either by calling waf in the subdirectory or by specifying it as part of
|
||||||
|
targets
|
||||||
|
|
||||||
|
# Will build only ArduCopter
|
||||||
|
cd ArduCopter; waf -j9; cd -
|
||||||
|
|
||||||
|
# From the top directory, note the board name used in the target
|
||||||
|
waf --targets=ArduCopter.linux
|
||||||
|
|
||||||
|
# List all the targets available
|
||||||
|
waf list
|
||||||
|
|
||||||
|
By default all the files produced by the build will be inside the build/
|
||||||
|
subdirectory. The binaries will also be there, with the name identifying
|
||||||
|
the target board.
|
||||||
|
|
||||||
|
To clean things up use
|
||||||
|
|
||||||
|
# Clean the build products, but keep configure information
|
||||||
|
waf clean
|
||||||
|
|
||||||
|
# Clean everything, will need to call configure again
|
||||||
|
waf distclean
|
||||||
|
|
||||||
|
using git to clean the files also work fine.
|
||||||
|
|
||||||
|
|
||||||
|
TODO: Add explanation on how the build system is organized once we
|
||||||
|
settle down.
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,131 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
SOURCE_EXTS = [
|
||||||
|
'*.S',
|
||||||
|
'*.c',
|
||||||
|
'*.cpp',
|
||||||
|
]
|
||||||
|
|
||||||
|
UTILITY_SOURCE_EXTS = [ 'utility/' + glob for glob in SOURCE_EXTS ]
|
||||||
|
|
||||||
|
# TODO: Once HAL patches get in, need to filter out the HAL based
|
||||||
|
# on the bld.env.BOARD.
|
||||||
|
COMMON_VEHICLE_DEPENDENT_LIBRARIES = [
|
||||||
|
'AP_ADC',
|
||||||
|
'AP_ADC_AnalogSource',
|
||||||
|
'AP_AHRS',
|
||||||
|
'AP_Airspeed',
|
||||||
|
'AP_Baro',
|
||||||
|
'AP_BattMonitor',
|
||||||
|
'AP_BoardConfig',
|
||||||
|
'AP_Buffer',
|
||||||
|
'AP_Common',
|
||||||
|
'AP_Compass',
|
||||||
|
'AP_Declination',
|
||||||
|
'AP_GPS',
|
||||||
|
'AP_HAL',
|
||||||
|
'AP_HAL_Empty',
|
||||||
|
'AP_InertialSensor',
|
||||||
|
'AP_Math',
|
||||||
|
'AP_Mission',
|
||||||
|
'AP_NavEKF',
|
||||||
|
'AP_NavEKF2',
|
||||||
|
'AP_Notify',
|
||||||
|
'AP_OpticalFlow',
|
||||||
|
'AP_Param',
|
||||||
|
'AP_Progmem',
|
||||||
|
'AP_Rally',
|
||||||
|
'AP_RangeFinder',
|
||||||
|
'AP_Scheduler',
|
||||||
|
'AP_SerialManager',
|
||||||
|
'AP_Terrain',
|
||||||
|
'AP_Vehicle',
|
||||||
|
'DataFlash',
|
||||||
|
'Filter',
|
||||||
|
'GCS_MAVLink',
|
||||||
|
'RC_Channel',
|
||||||
|
'SITL',
|
||||||
|
'StorageManager',
|
||||||
|
]
|
||||||
|
|
||||||
|
def _get_legacy_defines(name):
|
||||||
|
return [
|
||||||
|
'APM_BUILD_DIRECTORY=' + name,
|
||||||
|
'SKETCH="' + name + '"',
|
||||||
|
'SKETCHNAME="' + name + '"',
|
||||||
|
]
|
||||||
|
|
||||||
|
IGNORED_AP_LIBRARIES = [
|
||||||
|
'doc',
|
||||||
|
'AP_Limits',
|
||||||
|
'GCS_Console',
|
||||||
|
]
|
||||||
|
|
||||||
|
def get_all_libraries(bld):
|
||||||
|
libraries = []
|
||||||
|
for lib_node in bld.srcnode.ant_glob('libraries/*', dir=True):
|
||||||
|
name = lib_node.name
|
||||||
|
if name in IGNORED_AP_LIBRARIES:
|
||||||
|
continue
|
||||||
|
if name.startswith('AP_HAL'):
|
||||||
|
continue
|
||||||
|
libraries.append(name)
|
||||||
|
libraries.extend(['AP_HAL', 'AP_HAL_Empty'])
|
||||||
|
return libraries
|
||||||
|
|
||||||
|
def program(bld, **kw):
|
||||||
|
if 'target' in kw:
|
||||||
|
bld.fatal('Do not pass target for program')
|
||||||
|
if 'defines' not in kw:
|
||||||
|
kw['defines'] = []
|
||||||
|
if 'source' not in kw:
|
||||||
|
kw['source'] = bld.path.ant_glob(SOURCE_EXTS)
|
||||||
|
|
||||||
|
name = bld.path.name
|
||||||
|
kw['defines'].extend(_get_legacy_defines(name))
|
||||||
|
|
||||||
|
target = bld.bldnode.make_node(name + '.' + bld.env.BOARD)
|
||||||
|
bld.program(
|
||||||
|
target=target,
|
||||||
|
**kw
|
||||||
|
)
|
||||||
|
|
||||||
|
# NOTE: Code in libraries/ is compiled multiple times. So ensure each
|
||||||
|
# compilation is independent by providing different index for each.
|
||||||
|
# The need for this should disappear when libraries change to be
|
||||||
|
# independent of vehicle type.
|
||||||
|
LAST_IDX = 0
|
||||||
|
|
||||||
|
def _get_next_idx():
|
||||||
|
global LAST_IDX
|
||||||
|
LAST_IDX += 1
|
||||||
|
return LAST_IDX
|
||||||
|
|
||||||
|
def vehicle_stlib(bld, **kw):
|
||||||
|
if 'name' not in kw:
|
||||||
|
bld.fatal('Missing name for vehicle_stlib')
|
||||||
|
if 'vehicle' not in kw:
|
||||||
|
bld.fatal('Missing vehicle for vehicle_stlib')
|
||||||
|
if 'libraries' not in kw:
|
||||||
|
bld.fatal('Missing libraries for vehicle_stlib')
|
||||||
|
|
||||||
|
sources = []
|
||||||
|
libraries = kw['libraries'] + bld.env.AP_LIBRARIES
|
||||||
|
|
||||||
|
for lib_name in libraries:
|
||||||
|
lib_node = bld.srcnode.find_dir('libraries/' + lib_name)
|
||||||
|
if lib_node is None:
|
||||||
|
bld.fatal('Could not find library ' + lib_name)
|
||||||
|
lib_sources = lib_node.ant_glob(SOURCE_EXTS + UTILITY_SOURCE_EXTS)
|
||||||
|
sources.extend(lib_sources)
|
||||||
|
|
||||||
|
name = kw['name']
|
||||||
|
vehicle = kw['vehicle']
|
||||||
|
|
||||||
|
bld.stlib(
|
||||||
|
source=sources,
|
||||||
|
target=name,
|
||||||
|
defines=_get_legacy_defines(vehicle),
|
||||||
|
idx=_get_next_idx(),
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,13 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
if bld.env.BOARD in ['sitl']:
|
||||||
|
return
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,13 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
# TODO: Test code doesn't build. Fix or delete the test.
|
||||||
|
return
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,13 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
# TODO: Test code doesn't build. Fix or delete the test.
|
||||||
|
return
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,13 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
# TODO: Test code doesn't build. Fix or delete the test.
|
||||||
|
return
|
||||||
|
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
ardupilotwaf.program(
|
||||||
|
bld,
|
||||||
|
use='ap',
|
||||||
|
)
|
|
@ -0,0 +1,205 @@
|
||||||
|
#!/usr/bin/env python
|
||||||
|
# encoding: utf-8
|
||||||
|
|
||||||
|
import os.path
|
||||||
|
import sys
|
||||||
|
sys.path.insert(0, 'Tools/ardupilotwaf/')
|
||||||
|
|
||||||
|
import ardupilotwaf
|
||||||
|
|
||||||
|
# TODO: implement a command 'waf help' that shows the basic tasks a
|
||||||
|
# developer might want to do: e.g. how to configure a board, compile a
|
||||||
|
# vehicle, compile all the examples, add a new example. Should fit in
|
||||||
|
# less than a terminal screen, ideally commands should be copy
|
||||||
|
# pastable. Add the 'export waf="$PWD/waf"' trick to be copy-pastable
|
||||||
|
# as well.
|
||||||
|
|
||||||
|
# TODO: add support for unit tests.
|
||||||
|
|
||||||
|
# TODO: replace defines with the use of a generated config.h file
|
||||||
|
# this makes recompilation at least when defines change. which might
|
||||||
|
# be sufficient.
|
||||||
|
|
||||||
|
# TODO: set git version as part of build preparation.
|
||||||
|
|
||||||
|
# TODO: Check if we should simply use the signed 'waf' "binary" (after
|
||||||
|
# verifying it) instead of generating it ourselves from the sources.
|
||||||
|
|
||||||
|
# TODO: evaluate if we need shortcut commands for the common targets
|
||||||
|
# (vehicles). currently using waf --targets=NAME the target name must
|
||||||
|
# contain the board extension so make it less convenient, maybe hook
|
||||||
|
# to support automatic filling this extension?
|
||||||
|
|
||||||
|
PROJECT_CONFIG = dict(
|
||||||
|
CFLAGS=[
|
||||||
|
'-ffunction-sections',
|
||||||
|
'-fdata-sections',
|
||||||
|
'-fsigned-char',
|
||||||
|
|
||||||
|
'-Wformat',
|
||||||
|
'-Wall',
|
||||||
|
'-Wshadow',
|
||||||
|
'-Wpointer-arith',
|
||||||
|
'-Wcast-align',
|
||||||
|
'-Wno-unused-parameter',
|
||||||
|
'-Wno-missing-field-initializers',
|
||||||
|
],
|
||||||
|
|
||||||
|
CXXFLAGS=[
|
||||||
|
'-std=gnu++11',
|
||||||
|
|
||||||
|
'-fdata-sections',
|
||||||
|
'-ffunction-sections',
|
||||||
|
'-fno-exceptions',
|
||||||
|
'-fsigned-char',
|
||||||
|
|
||||||
|
'-Wformat',
|
||||||
|
'-Wall',
|
||||||
|
'-Wshadow',
|
||||||
|
'-Wpointer-arith',
|
||||||
|
'-Wcast-align',
|
||||||
|
'-Wno-unused-parameter',
|
||||||
|
'-Wno-missing-field-initializers',
|
||||||
|
'-Wno-reorder',
|
||||||
|
'-Werror=format-security',
|
||||||
|
'-Werror=array-bounds',
|
||||||
|
'-Wfatal-errors',
|
||||||
|
'-Werror=unused-but-set-variable',
|
||||||
|
'-Werror=uninitialized',
|
||||||
|
'-Werror=init-self',
|
||||||
|
'-Wno-missing-field-initializers',
|
||||||
|
],
|
||||||
|
|
||||||
|
LINKFLAGS=[
|
||||||
|
'-Wl,--gc-sections',
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
# NOTE: Keeping all the board definitions together so we can easily
|
||||||
|
# identify opportunities to simplify how it works. In the future might
|
||||||
|
# be worthy to keep board definitions in files of their own.
|
||||||
|
BOARDS = {
|
||||||
|
'sitl': dict(
|
||||||
|
DEFINES=[
|
||||||
|
'CONFIG_HAL_BOARD=HAL_BOARD_SITL',
|
||||||
|
'CONFIG_HAL_BOARD_SUBTYPE=HAL_BOARD_SUBTYPE_NONE',
|
||||||
|
],
|
||||||
|
|
||||||
|
LIB=[
|
||||||
|
'm',
|
||||||
|
'pthread',
|
||||||
|
],
|
||||||
|
|
||||||
|
AP_LIBRARIES=[
|
||||||
|
'AP_HAL_SITL',
|
||||||
|
'SITL',
|
||||||
|
],
|
||||||
|
),
|
||||||
|
|
||||||
|
'linux': dict(
|
||||||
|
DEFINES=[
|
||||||
|
'CONFIG_HAL_BOARD=HAL_BOARD_LINUX',
|
||||||
|
'CONFIG_HAL_BOARD_SUBTYPE=HAL_BOARD_SUBTYPE_LINUX_NONE',
|
||||||
|
],
|
||||||
|
|
||||||
|
LIB=[
|
||||||
|
'm',
|
||||||
|
'pthread',
|
||||||
|
'rt',
|
||||||
|
],
|
||||||
|
|
||||||
|
AP_LIBRARIES=[
|
||||||
|
'AP_HAL_Linux',
|
||||||
|
],
|
||||||
|
),
|
||||||
|
|
||||||
|
'minlure': dict(
|
||||||
|
DEFINES=[
|
||||||
|
'CONFIG_HAL_BOARD=HAL_BOARD_LINUX',
|
||||||
|
'CONFIG_HAL_BOARD_SUBTYPE=HAL_BOARD_SUBTYPE_LINUX_MINLURE',
|
||||||
|
],
|
||||||
|
|
||||||
|
LIB=[
|
||||||
|
'm',
|
||||||
|
'pthread',
|
||||||
|
'rt',
|
||||||
|
],
|
||||||
|
|
||||||
|
AP_LIBRARIES=[
|
||||||
|
'AP_HAL_Linux',
|
||||||
|
],
|
||||||
|
),
|
||||||
|
}
|
||||||
|
|
||||||
|
BOARDS_NAMES = sorted(list(BOARDS.keys()))
|
||||||
|
|
||||||
|
def options(opt):
|
||||||
|
opt.load('compiler_cxx compiler_c')
|
||||||
|
opt.add_option('--board',
|
||||||
|
action='store',
|
||||||
|
choices=BOARDS_NAMES,
|
||||||
|
default='sitl',
|
||||||
|
help='Target board to build, choices are %s' % BOARDS_NAMES)
|
||||||
|
|
||||||
|
def configure(cfg):
|
||||||
|
cfg.load('compiler_cxx compiler_c')
|
||||||
|
|
||||||
|
cfg.msg('Setting board to', cfg.options.board)
|
||||||
|
cfg.env.BOARD = cfg.options.board
|
||||||
|
board = BOARDS[cfg.env.BOARD]
|
||||||
|
|
||||||
|
# Always prepend so that arguments passed in the command line get the
|
||||||
|
# priority. Board configuration gets priority over the project
|
||||||
|
# configuration.
|
||||||
|
for k in board.keys():
|
||||||
|
cfg.env.prepend_value(k, board[k])
|
||||||
|
for k in PROJECT_CONFIG.keys():
|
||||||
|
cfg.env.prepend_value(k, PROJECT_CONFIG[k])
|
||||||
|
|
||||||
|
cfg.env.prepend_value('INCLUDES', [
|
||||||
|
cfg.srcnode.abspath() + '/libraries/'
|
||||||
|
])
|
||||||
|
|
||||||
|
# TODO: Investigate if code could be changed to not depend on the
|
||||||
|
# source absolute path.
|
||||||
|
cfg.env.prepend_value('DEFINES', [
|
||||||
|
'SKETCHBOOK="' + cfg.srcnode.abspath() + '"',
|
||||||
|
])
|
||||||
|
|
||||||
|
def collect_dirs_to_recurse(bld, glob, **kw):
|
||||||
|
dirs = []
|
||||||
|
for d in bld.srcnode.ant_glob(glob + '/wscript', **kw):
|
||||||
|
dirs.append(d.parent.relpath())
|
||||||
|
return dirs
|
||||||
|
|
||||||
|
def build(bld):
|
||||||
|
# NOTE: Static library with vehicle set to UNKNOWN, shared by all
|
||||||
|
# the tools and examples. This is the first step until the
|
||||||
|
# dependency on the vehicles is reduced. Later we may consider
|
||||||
|
# split into smaller pieces with well defined boundaries.
|
||||||
|
ardupilotwaf.vehicle_stlib(
|
||||||
|
bld,
|
||||||
|
name='ap',
|
||||||
|
vehicle='UNKNOWN',
|
||||||
|
libraries=ardupilotwaf.get_all_libraries(bld),
|
||||||
|
)
|
||||||
|
|
||||||
|
# TODO: Currently each vehicle also generate its own copy of the
|
||||||
|
# libraries. Fix this, or at least reduce the amount of
|
||||||
|
# vehicle-dependent libraries.
|
||||||
|
vehicles = collect_dirs_to_recurse(bld, '*')
|
||||||
|
|
||||||
|
# NOTE: we need to sort to ensure the repeated sources get the
|
||||||
|
# same index, and random ordering of the filesystem doesn't cause
|
||||||
|
# recompilation.
|
||||||
|
vehicles.sort()
|
||||||
|
|
||||||
|
tools = collect_dirs_to_recurse(bld, 'Tools/*')
|
||||||
|
examples = collect_dirs_to_recurse(bld, 'libraries/*/examples/*', excl='*/AP_HAL_*/* */SITL/*')
|
||||||
|
|
||||||
|
hal_examples = []
|
||||||
|
for l in bld.env.AP_LIBRARIES:
|
||||||
|
hal_examples.extend(collect_dirs_to_recurse(bld, 'libraries/' + l + '/examples/*'))
|
||||||
|
|
||||||
|
for d in vehicles + tools + examples + hal_examples:
|
||||||
|
bld.recurse(d)
|
Loading…
Reference in New Issue