From ec52df991cbf2438c5dbb3b60852dcafdb76721d Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Thu, 15 Oct 2015 19:09:54 -0300 Subject: [PATCH] build: compile only the HAL files needed by the board Instead of requiring every program to specify the HAL related modules, let the build system do it (in practice everything we compiled depended on HAL anyway). This allow including only the necessary files in the compilation. --- APMrover2/make.inc | 9 ---- AntennaTracker/make.inc | 8 ---- ArduCopter/make.inc | 9 ---- ArduPlane/make.inc | 9 ---- Tools/CPUInfo/make.inc | 6 --- Tools/Hello/make.inc | 6 --- Tools/Replay/make.inc | 6 --- .../AC_PID/examples/AC_PID_test/make.inc | 7 ---- .../AP_ADC/examples/AP_ADC_test/make.inc | 3 -- libraries/AP_AHRS/examples/AHRS_Test/make.inc | 7 ---- .../AP_Airspeed/examples/Airspeed/make.inc | 4 -- .../AP_Baro/examples/BARO_generic/make.inc | 7 ---- .../examples/AP_BattMonitor_test/make.inc | 5 --- .../AP_Common/examples/AP_Common/make.inc | 5 --- .../examples/AP_Compass_test/make.inc | 7 ---- .../examples/AP_Declination_test/make.inc | 2 - .../AP_GPS/examples/GPS_AUTO_test/make.inc | 6 --- .../examples/GPS_UBLOX_passthrough/make.inc | 5 --- libraries/AP_HAL/examples/AnalogIn/make.inc | 5 --- libraries/AP_HAL/examples/Printf/make.inc | 7 ---- libraries/AP_HAL/examples/RCInput/make.inc | 7 ---- .../examples/RCInputToRCOutput/make.inc | 7 ---- libraries/AP_HAL/examples/RCOutput/make.inc | 7 ---- libraries/AP_HAL/examples/Storage/make.inc | 7 ---- libraries/AP_HAL/examples/UART_test/make.inc | 7 ---- .../examples/ArduCopterLibs/make.inc | 2 - .../examples/ArduPlaneLibs/make.inc | 2 - libraries/AP_HAL_AVR/examples/Blink/make.inc | 2 - .../AP_HAL_AVR/examples/Console/make.inc | 2 - .../examples/I2CDriver_HMC5883L/make.inc | 2 - .../AP_HAL_AVR/examples/LCDTest/make.inc | 2 - .../AP_HAL_AVR/examples/RCInputTest/make.inc | 2 - .../AP_HAL_AVR/examples/RCJitterTest/make.inc | 2 - .../examples/RCPassthroughTest/make.inc | 2 - .../examples/SPIDriver_MPU6000/make.inc | 2 - .../AP_HAL_AVR/examples/Scheduler/make.inc | 2 - .../AP_HAL_AVR/examples/Semaphore/make.inc | 2 - .../AP_HAL_AVR/examples/Storage/make.inc | 2 - .../AP_HAL_AVR/examples/UARTDriver/make.inc | 2 - .../examples/UtilityStringTest/make.inc | 2 - .../examples/empty_example/make.inc | 4 -- .../examples/AP_Baro_BMP085_test/make.inc | 2 - .../examples/AnalogIn/make.inc | 2 - .../AP_HAL_FLYMAPLE/examples/Blink/make.inc | 2 - .../AP_HAL_FLYMAPLE/examples/Console/make.inc | 2 - .../examples/I2CDriver_HMC5883L/make.inc | 2 - .../AP_HAL_FLYMAPLE/examples/RCInput/make.inc | 2 - .../examples/RCPassthroughTest/make.inc | 2 - .../examples/SPIDriver/make.inc | 2 - .../examples/Scheduler/make.inc | 2 - .../examples/Semaphore/make.inc | 2 - .../AP_HAL_FLYMAPLE/examples/Storage/make.inc | 2 - .../examples/UARTDriver/make.inc | 2 - .../examples/UtilityStringTest/make.inc | 2 - .../examples/empty_example/make.inc | 2 - .../AP_HAL_Linux/examples/BusTest/make.inc | 5 +-- libraries/AP_HAL_PX4/examples/simple/make.inc | 6 --- .../examples/INS_generic/make.inc | 7 ---- .../examples/VibTest/make.inc | 6 --- libraries/AP_Math/examples/eulers/make.inc | 7 ---- libraries/AP_Math/examples/location/make.inc | 6 --- libraries/AP_Math/examples/polygon/make.inc | 3 -- libraries/AP_Math/examples/rotations/make.inc | 7 ---- .../examples/AP_Mission_test/make.inc | 6 --- .../examples/AP_Motors_Time_test/make.inc | 5 --- .../examples/AP_Motors_test/make.inc | 5 --- .../examples/trivial_AP_Mount/make.inc | 2 - .../examples/AP_Notify_test/make.inc | 5 --- .../examples/ToshibaLED_test/make.inc | 7 ---- .../examples/AP_OpticalFlow_test/make.inc | 3 -- .../examples/AP_Parachute_test/make.inc | 2 - libraries/AP_PerfMon/AP_PerfMon_test/make.inc | 2 - .../examples/RFIND_test/make.inc | 6 --- .../examples/Scheduler_test/make.inc | 7 ---- .../examples/DataFlash_test/make.inc | 7 ---- libraries/Filter/examples/Derivative/make.inc | 2 - libraries/Filter/examples/Filter/make.inc | 4 -- .../Filter/examples/LowPassFilter/make.inc | 2 - .../Filter/examples/LowPassFilter2p/make.inc | 4 -- .../GCS_Console/examples/Console/make.inc | 2 - .../GCS_MAVLink/examples/routing/make.inc | 8 ---- libraries/PID/examples/pid/make.inc | 4 -- .../RC_Channel/examples/RC_Channel/make.inc | 6 --- .../examples/StorageTest/make.inc | 8 ---- mk/sketch_sources.mk | 42 +++++++++++++++++++ 85 files changed, 43 insertions(+), 363 deletions(-) diff --git a/APMrover2/make.inc b/APMrover2/make.inc index 94aff52cea..ef3cc71e77 100644 --- a/APMrover2/make.inc +++ b/APMrover2/make.inc @@ -1,6 +1,5 @@ LIBRARIES = AP_Common LIBRARIES += AP_Progmem -LIBRARIES += AP_HAL LIBRARIES += AP_Menu LIBRARIES += AP_Param LIBRARIES += StorageManager @@ -35,20 +34,12 @@ LIBRARIES += AP_Airspeed LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += AP_RCMapper -LIBRARIES += SITL LIBRARIES += AP_Scheduler LIBRARIES += AP_Navigation LIBRARIES += APM_Control LIBRARIES += AP_L1_Control LIBRARIES += AP_BoardConfig LIBRARIES += AP_Frsky_Telem -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_VRBRAIN -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_Empty LIBRARIES += AP_Notify LIBRARIES += AP_BattMonitor LIBRARIES += AP_OpticalFlow diff --git a/AntennaTracker/make.inc b/AntennaTracker/make.inc index 094328ad6b..026909aa27 100644 --- a/AntennaTracker/make.inc +++ b/AntennaTracker/make.inc @@ -1,6 +1,5 @@ LIBRARIES += AP_Common LIBRARIES += AP_Progmem -LIBRARIES += AP_HAL LIBRARIES += AP_Param LIBRARIES += StorageManager LIBRARIES += AP_GPS @@ -17,7 +16,6 @@ LIBRARIES += GCS_MAVLink LIBRARIES += AP_SerialManager LIBRARIES += AP_Declination LIBRARIES += DataFlash -LIBRARIES += SITL LIBRARIES += PID LIBRARIES += AP_Scheduler LIBRARIES += AP_NavEKF @@ -33,9 +31,3 @@ LIBRARIES += RC_Channel LIBRARIES += AP_BoardConfig LIBRARIES += AP_OpticalFlow LIBRARIES += AP_RangeFinder -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_Empty diff --git a/ArduCopter/make.inc b/ArduCopter/make.inc index f4c6f166a1..d49016ef39 100644 --- a/ArduCopter/make.inc +++ b/ArduCopter/make.inc @@ -3,14 +3,6 @@ LIBRARIES += AP_Progmem LIBRARIES += AP_Menu LIBRARIES += AP_Param LIBRARIES += StorageManager -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_VRBRAIN -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_Empty LIBRARIES += GCS LIBRARIES += GCS_MAVLink LIBRARIES += AP_SerialManager @@ -53,7 +45,6 @@ LIBRARIES += AC_WPNav LIBRARIES += AC_Circle LIBRARIES += AP_Declination LIBRARIES += AC_Fence -LIBRARIES += SITL LIBRARIES += AP_Scheduler LIBRARIES += AP_RCMapper LIBRARIES += AP_Notify diff --git a/ArduPlane/make.inc b/ArduPlane/make.inc index 3b8371a152..a7ecdce635 100644 --- a/ArduPlane/make.inc +++ b/ArduPlane/make.inc @@ -1,4 +1,3 @@ -LIBRARIES = AP_HAL LIBRARIES += AP_Common LIBRARIES += AP_Progmem LIBRARIES += AP_Menu @@ -29,7 +28,6 @@ LIBRARIES += AP_SerialManager LIBRARIES += AP_Mount LIBRARIES += AP_Declination LIBRARIES += DataFlash -LIBRARIES += SITL LIBRARIES += AP_Scheduler LIBRARIES += AP_Navigation LIBRARIES += AP_L1_Control @@ -49,11 +47,4 @@ LIBRARIES += AP_ServoRelayEvents LIBRARIES += AP_Rally LIBRARIES += AP_OpticalFlow LIBRARIES += AP_RSSI -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_VRBRAIN LIBRARIES += AP_RPM diff --git a/Tools/CPUInfo/make.inc b/Tools/CPUInfo/make.inc index c8d1f40598..3beaded906 100644 --- a/Tools/CPUInfo/make.inc +++ b/Tools/CPUInfo/make.inc @@ -8,11 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +24,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/Tools/Hello/make.inc b/Tools/Hello/make.inc index 1366b5f7a6..99540c2bab 100644 --- a/Tools/Hello/make.inc +++ b/Tools/Hello/make.inc @@ -7,11 +7,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Notify @@ -21,7 +16,6 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += AP_NavEKF LIBRARIES += AP_RangeFinder LIBRARIES += AP_Mission diff --git a/Tools/Replay/make.inc b/Tools/Replay/make.inc index a8757f33ac..a5118dd295 100644 --- a/Tools/Replay/make.inc +++ b/Tools/Replay/make.inc @@ -3,11 +3,6 @@ LIBRARIES += AP_Progmem LIBRARIES += AP_Param LIBRARIES += StorageManager LIBRARIES += AP_Math -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_Empty LIBRARIES += AP_ADC LIBRARIES += AP_Declination LIBRARIES += AP_ADC_AnalogSource @@ -20,7 +15,6 @@ LIBRARIES += DataFlash LIBRARIES += GCS_MAVLink LIBRARIES += AP_GPS LIBRARIES += AP_AHRS -LIBRARIES += SITL LIBRARIES += AP_Compass LIBRARIES += AP_Baro LIBRARIES += AP_InertialSensor diff --git a/libraries/AC_PID/examples/AC_PID_test/make.inc b/libraries/AC_PID/examples/AC_PID_test/make.inc index fc58cdcea6..8d8a99a3e8 100644 --- a/libraries/AC_PID/examples/AC_PID_test/make.inc +++ b/libraries/AC_PID/examples/AC_PID_test/make.inc @@ -8,13 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_ADC/examples/AP_ADC_test/make.inc b/libraries/AP_ADC/examples/AP_ADC_test/make.inc index a83684fcc3..30f95b3a34 100644 --- a/libraries/AP_ADC/examples/AP_ADC_test/make.inc +++ b/libraries/AP_ADC/examples/AP_ADC_test/make.inc @@ -1,8 +1,5 @@ LIBRARIES += AP_ADC LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_AHRS/examples/AHRS_Test/make.inc b/libraries/AP_AHRS/examples/AHRS_Test/make.inc index fb9a1a80ac..cde1187dc9 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/make.inc +++ b/libraries/AP_AHRS/examples/AHRS_Test/make.inc @@ -9,12 +9,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -32,5 +26,4 @@ LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink LIBRARIES += RC_Channel -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_Airspeed/examples/Airspeed/make.inc b/libraries/AP_Airspeed/examples/Airspeed/make.inc index 27e81f342a..30594f97bc 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/make.inc +++ b/libraries/AP_Airspeed/examples/Airspeed/make.inc @@ -9,10 +9,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Baro/examples/BARO_generic/make.inc b/libraries/AP_Baro/examples/BARO_generic/make.inc index d046a3066e..68d7ad3f17 100644 --- a/libraries/AP_Baro/examples/BARO_generic/make.inc +++ b/libraries/AP_Baro/examples/BARO_generic/make.inc @@ -9,13 +9,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/make.inc b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/make.inc index db9ca25780..edcc9d6aed 100644 --- a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/make.inc +++ b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/make.inc @@ -8,11 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Common/examples/AP_Common/make.inc b/libraries/AP_Common/examples/AP_Common/make.inc index 96997580f4..5033b8b3fc 100644 --- a/libraries/AP_Common/examples/AP_Common/make.inc +++ b/libraries/AP_Common/examples/AP_Common/make.inc @@ -1,9 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_Compass/examples/AP_Compass_test/make.inc b/libraries/AP_Compass/examples/AP_Compass_test/make.inc index 99b416a920..f46c0e94ca 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/make.inc +++ b/libraries/AP_Compass/examples/AP_Compass_test/make.inc @@ -8,13 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_VRBRAIN LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Declination/examples/AP_Declination_test/make.inc b/libraries/AP_Declination/examples/AP_Declination_test/make.inc index 7585fd6e84..2de7da6ef2 100644 --- a/libraries/AP_Declination/examples/AP_Declination_test/make.inc +++ b/libraries/AP_Declination/examples/AP_Declination_test/make.inc @@ -1,8 +1,6 @@ LIBRARIES += AP_Buffer LIBRARIES += AP_Common LIBRARIES += AP_Declination -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/make.inc b/libraries/AP_GPS/examples/GPS_AUTO_test/make.inc index 457d572b15..e4dc3fea9c 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/make.inc +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/make.inc b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/make.inc index 3b42f51a98..f46c0e94ca 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/make.inc +++ b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/make.inc @@ -8,11 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_HAL/examples/AnalogIn/make.inc b/libraries/AP_HAL/examples/AnalogIn/make.inc index 96997580f4..5033b8b3fc 100644 --- a/libraries/AP_HAL/examples/AnalogIn/make.inc +++ b/libraries/AP_HAL/examples/AnalogIn/make.inc @@ -1,9 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL/examples/Printf/make.inc b/libraries/AP_HAL/examples/Printf/make.inc index b20141d400..edcc9d6aed 100644 --- a/libraries/AP_HAL/examples/Printf/make.inc +++ b/libraries/AP_HAL/examples/Printf/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -28,5 +22,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL/examples/RCInput/make.inc b/libraries/AP_HAL/examples/RCInput/make.inc index 5378923665..f46c0e94ca 100644 --- a/libraries/AP_HAL/examples/RCInput/make.inc +++ b/libraries/AP_HAL/examples/RCInput/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL/examples/RCInputToRCOutput/make.inc b/libraries/AP_HAL/examples/RCInputToRCOutput/make.inc index 5378923665..f46c0e94ca 100644 --- a/libraries/AP_HAL/examples/RCInputToRCOutput/make.inc +++ b/libraries/AP_HAL/examples/RCInputToRCOutput/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL/examples/RCOutput/make.inc b/libraries/AP_HAL/examples/RCOutput/make.inc index 5378923665..f46c0e94ca 100644 --- a/libraries/AP_HAL/examples/RCOutput/make.inc +++ b/libraries/AP_HAL/examples/RCOutput/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL/examples/Storage/make.inc b/libraries/AP_HAL/examples/Storage/make.inc index 5378923665..f46c0e94ca 100644 --- a/libraries/AP_HAL/examples/Storage/make.inc +++ b/libraries/AP_HAL/examples/Storage/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL/examples/UART_test/make.inc b/libraries/AP_HAL/examples/UART_test/make.inc index 5378923665..f46c0e94ca 100644 --- a/libraries/AP_HAL/examples/UART_test/make.inc +++ b/libraries/AP_HAL/examples/UART_test/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc index 8179acdfeb..d9714af044 100644 --- a/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc +++ b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc @@ -12,8 +12,6 @@ LIBRARIES += AP_Compass LIBRARIES += AP_Curve LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_InertialNav LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math diff --git a/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc index 03bc15acf9..1244972a7c 100644 --- a/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc +++ b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc @@ -10,8 +10,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += APM_Control diff --git a/libraries/AP_HAL_AVR/examples/Blink/make.inc b/libraries/AP_HAL_AVR/examples/Blink/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/Blink/make.inc +++ b/libraries/AP_HAL_AVR/examples/Blink/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/Console/make.inc b/libraries/AP_HAL_AVR/examples/Console/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/Console/make.inc +++ b/libraries/AP_HAL_AVR/examples/Console/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc +++ b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/LCDTest/make.inc b/libraries/AP_HAL_AVR/examples/LCDTest/make.inc index b454167fdd..f7222d8a8f 100644 --- a/libraries/AP_HAL_AVR/examples/LCDTest/make.inc +++ b/libraries/AP_HAL_AVR/examples/LCDTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc b/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc +++ b/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc b/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc +++ b/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc +++ b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc +++ b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/Scheduler/make.inc b/libraries/AP_HAL_AVR/examples/Scheduler/make.inc index b454167fdd..f7222d8a8f 100644 --- a/libraries/AP_HAL_AVR/examples/Scheduler/make.inc +++ b/libraries/AP_HAL_AVR/examples/Scheduler/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/Semaphore/make.inc b/libraries/AP_HAL_AVR/examples/Semaphore/make.inc index b454167fdd..f7222d8a8f 100644 --- a/libraries/AP_HAL_AVR/examples/Semaphore/make.inc +++ b/libraries/AP_HAL_AVR/examples/Semaphore/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/Storage/make.inc b/libraries/AP_HAL_AVR/examples/Storage/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/Storage/make.inc +++ b/libraries/AP_HAL_AVR/examples/Storage/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc b/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc +++ b/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc b/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc index 89315e2830..5033b8b3fc 100644 --- a/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc +++ b/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_Empty/examples/empty_example/make.inc b/libraries/AP_HAL_Empty/examples/empty_example/make.inc index e0ee647d91..5033b8b3fc 100644 --- a/libraries/AP_HAL_Empty/examples/empty_example/make.inc +++ b/libraries/AP_HAL_Empty/examples/empty_example/make.inc @@ -1,8 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/make.inc index d6c50bca61..4eef579242 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/make.inc @@ -2,8 +2,6 @@ LIBRARIES += AP_ADC LIBRARIES += AP_Baro LIBRARIES += AP_Buffer LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Blink/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/Blink/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Blink/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/Blink/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Console/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/Console/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Console/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/Console/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/RCInput/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/RCInput/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/RCInput/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/RCInput/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Storage/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/Storage/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Storage/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/Storage/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_FLYMAPLE/examples/empty_example/make.inc b/libraries/AP_HAL_FLYMAPLE/examples/empty_example/make.inc index efce9e0832..f7222d8a8f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/empty_example/make.inc +++ b/libraries/AP_HAL_FLYMAPLE/examples/empty_example/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_FLYMAPLE LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_HAL_Linux/examples/BusTest/make.inc b/libraries/AP_HAL_Linux/examples/BusTest/make.inc index 3f89190049..2a089fa174 100644 --- a/libraries/AP_HAL_Linux/examples/BusTest/make.inc +++ b/libraries/AP_HAL_Linux/examples/BusTest/make.inc @@ -1,9 +1,6 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem LIBRARIES += StorageManager -LIBRARIES += AP_ADC \ No newline at end of file +LIBRARIES += AP_ADC diff --git a/libraries/AP_HAL_PX4/examples/simple/make.inc b/libraries/AP_HAL_PX4/examples/simple/make.inc index 0390e78ca7..f46c0e94ca 100644 --- a/libraries/AP_HAL_PX4/examples/simple/make.inc +++ b/libraries/AP_HAL_PX4/examples/simple/make.inc @@ -8,11 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -28,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_InertialSensor/examples/INS_generic/make.inc b/libraries/AP_InertialSensor/examples/INS_generic/make.inc index 8b81bf1665..f46c0e94ca 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/make.inc +++ b/libraries/AP_InertialSensor/examples/INS_generic/make.inc @@ -8,13 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_InertialSensor/examples/VibTest/make.inc b/libraries/AP_InertialSensor/examples/VibTest/make.inc index 3b58950625..f46c0e94ca 100644 --- a/libraries/AP_InertialSensor/examples/VibTest/make.inc +++ b/libraries/AP_InertialSensor/examples/VibTest/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Math/examples/eulers/make.inc b/libraries/AP_Math/examples/eulers/make.inc index f9e7eced33..ceae92b959 100644 --- a/libraries/AP_Math/examples/eulers/make.inc +++ b/libraries/AP_Math/examples/eulers/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -28,6 +22,5 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager LIBRARIES += AP_OpticalFlow diff --git a/libraries/AP_Math/examples/location/make.inc b/libraries/AP_Math/examples/location/make.inc index 851f23e8b4..f667199307 100644 --- a/libraries/AP_Math/examples/location/make.inc +++ b/libraries/AP_Math/examples/location/make.inc @@ -8,11 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -28,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/AP_Math/examples/polygon/make.inc b/libraries/AP_Math/examples/polygon/make.inc index 1f96c6122a..5033b8b3fc 100644 --- a/libraries/AP_Math/examples/polygon/make.inc +++ b/libraries/AP_Math/examples/polygon/make.inc @@ -1,7 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/AP_Math/examples/rotations/make.inc b/libraries/AP_Math/examples/rotations/make.inc index 37270bb1c2..348a6a7084 100644 --- a/libraries/AP_Math/examples/rotations/make.inc +++ b/libraries/AP_Math/examples/rotations/make.inc @@ -1,16 +1,9 @@ LIBRARIES += AP_Common LIBRARIES += AP_Progmem LIBRARIES += AP_Param -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_Math LIBRARIES += Filter LIBRARIES += AP_ADC -LIBRARIES += SITL LIBRARIES += AP_Compass LIBRARIES += AP_Baro LIBRARIES += AP_Notify diff --git a/libraries/AP_Mission/examples/AP_Mission_test/make.inc b/libraries/AP_Mission/examples/AP_Mission_test/make.inc index 641244445a..aebeec7c0d 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/make.inc +++ b/libraries/AP_Mission/examples/AP_Mission_test/make.inc @@ -10,11 +10,6 @@ LIBRARIES += AP_Compass LIBRARIES += AP_Curve LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,6 +24,5 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager LIBRARIES += AP_OpticalFlow diff --git a/libraries/AP_Motors/examples/AP_Motors_Time_test/make.inc b/libraries/AP_Motors/examples/AP_Motors_Time_test/make.inc index b8f4c9dea4..53e15fb15b 100644 --- a/libraries/AP_Motors/examples/AP_Motors_Time_test/make.inc +++ b/libraries/AP_Motors/examples/AP_Motors_Time_test/make.inc @@ -9,11 +9,6 @@ LIBRARIES += AP_Compass LIBRARIES += AP_Curve LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Motors/examples/AP_Motors_test/make.inc b/libraries/AP_Motors/examples/AP_Motors_test/make.inc index b8f4c9dea4..53e15fb15b 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/make.inc +++ b/libraries/AP_Motors/examples/AP_Motors_test/make.inc @@ -9,11 +9,6 @@ LIBRARIES += AP_Compass LIBRARIES += AP_Curve LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Mount/examples/trivial_AP_Mount/make.inc b/libraries/AP_Mount/examples/trivial_AP_Mount/make.inc index e00d636430..531e0b8b3f 100644 --- a/libraries/AP_Mount/examples/trivial_AP_Mount/make.inc +++ b/libraries/AP_Mount/examples/trivial_AP_Mount/make.inc @@ -9,8 +9,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Notify/examples/AP_Notify_test/make.inc b/libraries/AP_Notify/examples/AP_Notify_test/make.inc index 9539e59621..638b40291f 100644 --- a/libraries/AP_Notify/examples/AP_Notify_test/make.inc +++ b/libraries/AP_Notify/examples/AP_Notify_test/make.inc @@ -1,9 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_Math LIBRARIES += AP_Notify LIBRARIES += AP_Param diff --git a/libraries/AP_Notify/examples/ToshibaLED_test/make.inc b/libraries/AP_Notify/examples/ToshibaLED_test/make.inc index d289d477e9..0c9de6fa0d 100644 --- a/libraries/AP_Notify/examples/ToshibaLED_test/make.inc +++ b/libraries/AP_Notify/examples/ToshibaLED_test/make.inc @@ -8,13 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/make.inc b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/make.inc index a9ad5405de..f3d18aeb56 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/make.inc +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/make.inc @@ -8,9 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Parachute/examples/AP_Parachute_test/make.inc b/libraries/AP_Parachute/examples/AP_Parachute_test/make.inc index 66c69e1fc2..c38d76f87f 100644 --- a/libraries/AP_Parachute/examples/AP_Parachute_test/make.inc +++ b/libraries/AP_Parachute/examples/AP_Parachute_test/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Notify LIBRARIES += AP_Parachute diff --git a/libraries/AP_PerfMon/AP_PerfMon_test/make.inc b/libraries/AP_PerfMon/AP_PerfMon_test/make.inc index 860c89a041..23185ed3ca 100644 --- a/libraries/AP_PerfMon/AP_PerfMon_test/make.inc +++ b/libraries/AP_PerfMon/AP_PerfMon_test/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_PerfMon diff --git a/libraries/AP_RangeFinder/examples/RFIND_test/make.inc b/libraries/AP_RangeFinder/examples/RFIND_test/make.inc index 1d420efc87..f46c0e94ca 100644 --- a/libraries/AP_RangeFinder/examples/RFIND_test/make.inc +++ b/libraries/AP_RangeFinder/examples/RFIND_test/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/make.inc b/libraries/AP_Scheduler/examples/Scheduler_test/make.inc index e6453d292f..6875c2a64e 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/make.inc +++ b/libraries/AP_Scheduler/examples/Scheduler_test/make.inc @@ -9,12 +9,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL -LIBRARIES += AP_HAL_Linux LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -30,6 +24,5 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager LIBRARIES += AP_OpticalFlow diff --git a/libraries/DataFlash/examples/DataFlash_test/make.inc b/libraries/DataFlash/examples/DataFlash_test/make.inc index 158ad8a388..3beaded906 100644 --- a/libraries/DataFlash/examples/DataFlash_test/make.inc +++ b/libraries/DataFlash/examples/DataFlash_test/make.inc @@ -8,12 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -30,5 +24,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/Filter/examples/Derivative/make.inc b/libraries/Filter/examples/Derivative/make.inc index cf8db3f312..6b2740ddf9 100644 --- a/libraries/Filter/examples/Derivative/make.inc +++ b/libraries/Filter/examples/Derivative/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/Filter/examples/Filter/make.inc b/libraries/Filter/examples/Filter/make.inc index 79fbd01a93..6b2740ddf9 100644 --- a/libraries/Filter/examples/Filter/make.inc +++ b/libraries/Filter/examples/Filter/make.inc @@ -1,8 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/Filter/examples/LowPassFilter/make.inc b/libraries/Filter/examples/LowPassFilter/make.inc index cf8db3f312..6b2740ddf9 100644 --- a/libraries/Filter/examples/LowPassFilter/make.inc +++ b/libraries/Filter/examples/LowPassFilter/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/Filter/examples/LowPassFilter2p/make.inc b/libraries/Filter/examples/LowPassFilter2p/make.inc index 0609b30549..6b2740ddf9 100644 --- a/libraries/Filter/examples/LowPassFilter2p/make.inc +++ b/libraries/Filter/examples/LowPassFilter2p/make.inc @@ -1,8 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_PX4 LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/GCS_Console/examples/Console/make.inc b/libraries/GCS_Console/examples/Console/make.inc index c6df147fbf..cb5c4fd62d 100644 --- a/libraries/GCS_Console/examples/Console/make.inc +++ b/libraries/GCS_Console/examples/Console/make.inc @@ -1,6 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR LIBRARIES += AP_Math LIBRARIES += AP_Mission LIBRARIES += AP_Param diff --git a/libraries/GCS_MAVLink/examples/routing/make.inc b/libraries/GCS_MAVLink/examples/routing/make.inc index 52cda883ea..f46c0e94ca 100644 --- a/libraries/GCS_MAVLink/examples/routing/make.inc +++ b/libraries/GCS_MAVLink/examples/routing/make.inc @@ -8,13 +8,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -30,5 +23,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/PID/examples/pid/make.inc b/libraries/PID/examples/pid/make.inc index e8943fe0be..bfb913efe3 100644 --- a/libraries/PID/examples/pid/make.inc +++ b/libraries/PID/examples/pid/make.inc @@ -1,8 +1,4 @@ LIBRARIES += AP_Common -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_Math LIBRARIES += AP_Param LIBRARIES += AP_Progmem diff --git a/libraries/RC_Channel/examples/RC_Channel/make.inc b/libraries/RC_Channel/examples/RC_Channel/make.inc index 1b5e7b3a5a..fc2f90e91f 100644 --- a/libraries/RC_Channel/examples/RC_Channel/make.inc +++ b/libraries/RC_Channel/examples/RC_Channel/make.inc @@ -7,11 +7,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -28,5 +23,4 @@ LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink LIBRARIES += RC_Channel -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/libraries/StorageManager/examples/StorageTest/make.inc b/libraries/StorageManager/examples/StorageTest/make.inc index 94c9db0219..ff23f1bc49 100644 --- a/libraries/StorageManager/examples/StorageTest/make.inc +++ b/libraries/StorageManager/examples/StorageTest/make.inc @@ -7,13 +7,6 @@ LIBRARIES += AP_Common LIBRARIES += AP_Compass LIBRARIES += AP_Declination LIBRARIES += AP_GPS -LIBRARIES += AP_HAL -LIBRARIES += AP_HAL_AVR -LIBRARIES += AP_HAL_Empty -LIBRARIES += AP_HAL_FLYMAPLE -LIBRARIES += AP_HAL_Linux -LIBRARIES += AP_HAL_PX4 -LIBRARIES += AP_HAL_SITL LIBRARIES += AP_InertialSensor LIBRARIES += AP_Math LIBRARIES += AP_Mission @@ -29,5 +22,4 @@ LIBRARIES += AP_Vehicle LIBRARIES += DataFlash LIBRARIES += Filter LIBRARIES += GCS_MAVLink -LIBRARIES += SITL LIBRARIES += StorageManager diff --git a/mk/sketch_sources.mk b/mk/sketch_sources.mk index 28b3155607..0de2cdcfdf 100644 --- a/mk/sketch_sources.mk +++ b/mk/sketch_sources.mk @@ -21,6 +21,48 @@ SKETCHOBJS := $(addsuffix .o,$(basename $(SKETCHOBJS))) include $(MAKE_INC) LIBTOKENS := $(LIBRARIES) + +# HAL and board specific libraries are included here. +LIBTOKENS += \ + AP_HAL \ + AP_HAL_Empty + +ifeq ($(HAL_BOARD),HAL_BOARD_APM1) +LIBTOKENS += \ + AP_HAL_APM +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_APM2) +LIBTOKENS += \ + AP_HAL_APM +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_SITL) +LIBTOKENS += \ + AP_HAL_SITL \ + SITL +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_LINUX) +LIBTOKENS += \ + AP_HAL_Linux +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_PX4) +LIBTOKENS += \ + AP_HAL_PX4 +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_VRBRAIN) +LIBTOKENS += \ + AP_HAL_VRBRAIN +endif + +ifeq ($(HAL_BOARD),HAL_BOARD_FLYMAPLE) +LIBTOKENS += \ + AP_HAL_FLYMAPLE +endif + # # Find sketchbook libraries referenced by the sketch. #