Browse Source

waf: add waf support

mission-4.1.18
Caio Marcelo de Oliveira Filho 9 years ago committed by Andrew Tridgell
parent
commit
6e7b73610d
  1. 2
      .gitignore
  2. 31
      APMrover2/wscript
  3. 20
      AntennaTracker/wscript
  4. 41
      ArduCopter/wscript
  5. 35
      ArduPlane/wscript
  6. 58
      README_waf.txt
  7. 10
      Tools/CPUInfo/wscript
  8. 10
      Tools/Hello/wscript
  9. 10
      Tools/Replay/wscript
  10. 0
      Tools/ardupilotwaf/__init__.py
  11. 131
      Tools/ardupilotwaf/ardupilotwaf.py
  12. 10
      libraries/AC_PID/examples/AC_PID_test/wscript
  13. 13
      libraries/AP_ADC/examples/AP_ADC_test/wscript
  14. 10
      libraries/AP_AHRS/examples/AHRS_Test/wscript
  15. 10
      libraries/AP_Airspeed/examples/Airspeed/wscript
  16. 10
      libraries/AP_Baro/examples/BARO_generic/wscript
  17. 10
      libraries/AP_BattMonitor/examples/AP_BattMonitor_test/wscript
  18. 10
      libraries/AP_Common/examples/AP_Common/wscript
  19. 10
      libraries/AP_Compass/examples/AP_Compass_test/wscript
  20. 10
      libraries/AP_Declination/examples/AP_Declination_test/wscript
  21. 10
      libraries/AP_GPS/examples/GPS_AUTO_test/wscript
  22. 10
      libraries/AP_GPS/examples/GPS_UBLOX_passthrough/wscript
  23. 10
      libraries/AP_HAL/examples/AnalogIn/wscript
  24. 10
      libraries/AP_HAL/examples/Printf/wscript
  25. 10
      libraries/AP_HAL/examples/RCInput/wscript
  26. 10
      libraries/AP_HAL/examples/RCInputToRCOutput/wscript
  27. 10
      libraries/AP_HAL/examples/RCOutput/wscript
  28. 10
      libraries/AP_HAL/examples/Storage/wscript
  29. 10
      libraries/AP_HAL/examples/UART_test/wscript
  30. 10
      libraries/AP_HAL_AVR/examples/ArduCopterLibs/wscript
  31. 10
      libraries/AP_HAL_AVR/examples/ArduPlaneLibs/wscript
  32. 10
      libraries/AP_HAL_AVR/examples/Blink/wscript
  33. 10
      libraries/AP_HAL_AVR/examples/Console/wscript
  34. 10
      libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/wscript
  35. 10
      libraries/AP_HAL_AVR/examples/LCDTest/wscript
  36. 10
      libraries/AP_HAL_AVR/examples/RCInputTest/wscript
  37. 10
      libraries/AP_HAL_AVR/examples/RCJitterTest/wscript
  38. 10
      libraries/AP_HAL_AVR/examples/RCPassthroughTest/wscript
  39. 10
      libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/wscript
  40. 10
      libraries/AP_HAL_AVR/examples/Scheduler/wscript
  41. 10
      libraries/AP_HAL_AVR/examples/Semaphore/wscript
  42. 10
      libraries/AP_HAL_AVR/examples/Storage/wscript
  43. 10
      libraries/AP_HAL_AVR/examples/UARTDriver/wscript
  44. 10
      libraries/AP_HAL_AVR/examples/UtilityStringTest/wscript
  45. 10
      libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/wscript
  46. 10
      libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/wscript
  47. 10
      libraries/AP_HAL_FLYMAPLE/examples/Blink/wscript
  48. 10
      libraries/AP_HAL_FLYMAPLE/examples/Console/wscript
  49. 10
      libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/wscript
  50. 10
      libraries/AP_HAL_FLYMAPLE/examples/RCInput/wscript
  51. 10
      libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/wscript
  52. 10
      libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/wscript
  53. 10
      libraries/AP_HAL_FLYMAPLE/examples/Scheduler/wscript
  54. 10
      libraries/AP_HAL_FLYMAPLE/examples/Semaphore/wscript
  55. 10
      libraries/AP_HAL_FLYMAPLE/examples/Storage/wscript
  56. 10
      libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/wscript
  57. 10
      libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/wscript
  58. 10
      libraries/AP_HAL_FLYMAPLE/examples/empty_example/wscript
  59. 10
      libraries/AP_HAL_Linux/examples/BusTest/wscript
  60. 10
      libraries/AP_HAL_PX4/examples/simple/wscript
  61. 10
      libraries/AP_InertialSensor/examples/INS_generic/wscript
  62. 10
      libraries/AP_InertialSensor/examples/VibTest/wscript
  63. 10
      libraries/AP_Math/examples/eulers/wscript
  64. 10
      libraries/AP_Math/examples/location/wscript
  65. 10
      libraries/AP_Math/examples/polygon/wscript
  66. 10
      libraries/AP_Math/examples/rotations/wscript
  67. 10
      libraries/AP_Mission/examples/AP_Mission_test/wscript
  68. 13
      libraries/AP_Motors/examples/AP_Motors_Time_test/wscript
  69. 13
      libraries/AP_Motors/examples/AP_Motors_test/wscript
  70. 10
      libraries/AP_Mount/examples/trivial_AP_Mount/wscript
  71. 10
      libraries/AP_Notify/examples/AP_Notify_test/wscript
  72. 10
      libraries/AP_Notify/examples/ToshibaLED_test/wscript
  73. 10
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/wscript
  74. 10
      libraries/AP_Parachute/examples/AP_Parachute_test/wscript
  75. 10
      libraries/AP_RangeFinder/examples/RFIND_test/wscript
  76. 10
      libraries/AP_Scheduler/examples/Scheduler_test/wscript
  77. 10
      libraries/DataFlash/examples/DataFlash_test/wscript
  78. 10
      libraries/Filter/examples/Derivative/wscript
  79. 10
      libraries/Filter/examples/Filter/wscript
  80. 10
      libraries/Filter/examples/LowPassFilter/wscript
  81. 10
      libraries/Filter/examples/LowPassFilter2p/wscript
  82. 13
      libraries/GCS_Console/examples/Console/wscript
  83. 10
      libraries/GCS_MAVLink/examples/routing/wscript
  84. 10
      libraries/PID/examples/pid/wscript
  85. 10
      libraries/RC_Channel/examples/RC_Channel/wscript
  86. 10
      libraries/StorageManager/examples/StorageTest/wscript
  87. 205
      wscript

2
.gitignore vendored

@ -29,6 +29,8 @@ @@ -29,6 +29,8 @@
.settings/
.autotools
.vagrant
/.lock-waf*
/.waf*
/tmp/*
/Tools/ArdupilotMegaPlanner/3DRRadio/bin
/Tools/ArdupilotMegaPlanner/3DRRadio/obj

31
APMrover2/wscript

@ -0,0 +1,31 @@ @@ -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',
)

20
AntennaTracker/wscript

@ -0,0 +1,20 @@ @@ -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',
)

41
ArduCopter/wscript

@ -0,0 +1,41 @@ @@ -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',
)

35
ArduPlane/wscript

@ -0,0 +1,35 @@ @@ -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',
)

58
README_waf.txt

@ -0,0 +1,58 @@ @@ -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.

10
Tools/CPUInfo/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
Tools/Hello/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
Tools/Replay/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

0
Tools/ardupilotwaf/__init__.py

131
Tools/ardupilotwaf/ardupilotwaf.py

@ -0,0 +1,131 @@ @@ -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(),
)

10
libraries/AC_PID/examples/AC_PID_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

13
libraries/AP_ADC/examples/AP_ADC_test/wscript

@ -0,0 +1,13 @@ @@ -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',
)

10
libraries/AP_AHRS/examples/AHRS_Test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Airspeed/examples/Airspeed/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Baro/examples/BARO_generic/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_BattMonitor/examples/AP_BattMonitor_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Common/examples/AP_Common/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Compass/examples/AP_Compass_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Declination/examples/AP_Declination_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_GPS/examples/GPS_AUTO_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_GPS/examples/GPS_UBLOX_passthrough/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/AnalogIn/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/Printf/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/RCInput/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/RCInputToRCOutput/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/RCOutput/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/Storage/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL/examples/UART_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/ArduCopterLibs/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/ArduPlaneLibs/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/Blink/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/Console/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/LCDTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/RCInputTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/RCJitterTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/RCPassthroughTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/Scheduler/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/Semaphore/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/Storage/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/UARTDriver/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_AVR/examples/UtilityStringTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/Blink/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/Console/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/RCInput/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/Scheduler/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/Semaphore/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/Storage/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_FLYMAPLE/examples/empty_example/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_Linux/examples/BusTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_HAL_PX4/examples/simple/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_InertialSensor/examples/INS_generic/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_InertialSensor/examples/VibTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Math/examples/eulers/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Math/examples/location/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Math/examples/polygon/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Math/examples/rotations/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Mission/examples/AP_Mission_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

13
libraries/AP_Motors/examples/AP_Motors_Time_test/wscript

@ -0,0 +1,13 @@ @@ -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',
)

13
libraries/AP_Motors/examples/AP_Motors_test/wscript

@ -0,0 +1,13 @@ @@ -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',
)

10
libraries/AP_Mount/examples/trivial_AP_Mount/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Notify/examples/AP_Notify_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Notify/examples/ToshibaLED_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Parachute/examples/AP_Parachute_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_RangeFinder/examples/RFIND_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/AP_Scheduler/examples/Scheduler_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/DataFlash/examples/DataFlash_test/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/Filter/examples/Derivative/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/Filter/examples/Filter/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/Filter/examples/LowPassFilter/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/Filter/examples/LowPassFilter2p/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

13
libraries/GCS_Console/examples/Console/wscript

@ -0,0 +1,13 @@ @@ -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',
)

10
libraries/GCS_MAVLink/examples/routing/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/PID/examples/pid/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/RC_Channel/examples/RC_Channel/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

10
libraries/StorageManager/examples/StorageTest/wscript

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.program(
bld,
use='ap',
)

205
wscript

@ -0,0 +1,205 @@ @@ -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…
Cancel
Save