diff --git a/ArduCopter/Arduino.h b/ArduCopter/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/ArduPlane/Arduino.h b/ArduPlane/Arduino.h deleted file mode 100644 index 5c2de86bb0..0000000000 --- a/ArduPlane/Arduino.h +++ /dev/null @@ -1,3 +0,0 @@ -/* Stub Arduino.h header for use with AP_HAL. (The preprocessor will put - * #include "Arduino.h" on top no matter what, but we dont have the Arduino - * core in the compiler's path to find one.) */ diff --git a/libraries/AC_PID/examples/AC_PID_test/Arduino.h b/libraries/AC_PID/examples/AC_PID_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/APM_OBC/examples/trivial_APM_OBC/Arduino.h b/libraries/APM_OBC/examples/trivial_APM_OBC/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_ADC/examples/AP_ADC_test/Arduino.h b/libraries/AP_ADC/examples/AP_ADC_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_AHRS/examples/AHRS_Test/Arduino.h b/libraries/AP_AHRS/examples/AHRS_Test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Airspeed/examples/Airspeed/Arduino.h b/libraries/AP_Airspeed/examples/Airspeed/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Baro/examples/AP_Baro_BMP085_test/Arduino.h b/libraries/AP_Baro/examples/AP_Baro_BMP085_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/Arduino.h b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Compass/examples/AP_Compass_test/Arduino.h b/libraries/AP_Compass/examples/AP_Compass_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Declination/examples/AP_Declination_test/Arduino.h b/libraries/AP_Declination/examples/AP_Declination_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_GPS/examples/GPS_406_test/Arduino.h b/libraries/AP_GPS/examples/GPS_406_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/Arduino.h b/libraries/AP_GPS/examples/GPS_AUTO_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_GPS/examples/GPS_MTK_test/Arduino.h b/libraries/AP_GPS/examples/GPS_MTK_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_GPS/examples/GPS_NMEA_test/Arduino.h b/libraries/AP_GPS/examples/GPS_NMEA_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_test/Arduino.h b/libraries/AP_GPS/examples/GPS_UBLOX_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/AnalogIn/Arduino.h b/libraries/AP_HAL_AVR/examples/AnalogIn/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/ArduCopterLibs/Arduino.h b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/Arduino.h b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/Blink/Arduino.h b/libraries/AP_HAL_AVR/examples/Blink/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/Console/Arduino.h b/libraries/AP_HAL_AVR/examples/Console/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/Arduino.h b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/LCDTest/Arduino.h b/libraries/AP_HAL_AVR/examples/LCDTest/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/RCInputTest/Arduino.h b/libraries/AP_HAL_AVR/examples/RCInputTest/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/Arduino.h b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/Arduino.h b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/Scheduler/Arduino.h b/libraries/AP_HAL_AVR/examples/Scheduler/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/Storage/Arduino.h b/libraries/AP_HAL_AVR/examples/Storage/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_AVR/examples/UARTDriver/Arduino.h b/libraries/AP_HAL_AVR/examples/UARTDriver/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_HAL_PX4/examples/simple/Arduino.h b/libraries/AP_HAL_PX4/examples/simple/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_InertialNav/examples/AP_InertialNav_test/Arduino.h b/libraries/AP_InertialNav/examples/AP_InertialNav_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_InertialSensor/examples/MPU6000/Arduino.h b/libraries/AP_InertialSensor/examples/MPU6000/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_LeadFilter/examples/AP_LeadFilter/Arduino.h b/libraries/AP_LeadFilter/examples/AP_LeadFilter/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Math/examples/eulers/Arduino.h b/libraries/AP_Math/examples/eulers/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Math/examples/location/Arduino.h b/libraries/AP_Math/examples/location/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Math/examples/polygon/Arduino.h b/libraries/AP_Math/examples/polygon/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Math/examples/rotations/Arduino.h b/libraries/AP_Math/examples/rotations/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Menu/examples/menu/Arduino.h b/libraries/AP_Menu/examples/menu/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Motors/examples/AP_Motors_test/Arduino.h b/libraries/AP_Motors/examples/AP_Motors_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_Mount/examples/trivial_AP_Mount/Arduino.h b/libraries/AP_Mount/examples/trivial_AP_Mount/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/Arduino.h b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/AP_RangeFinder/examples/MaxsonarXL_test/Arduino.h b/libraries/AP_RangeFinder/examples/MaxsonarXL_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/DataFlash/examples/DataFlash_test/Arduino.h b/libraries/DataFlash/examples/DataFlash_test/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/Filter/examples/Derivative/Arduino.h b/libraries/Filter/examples/Derivative/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/Filter/examples/Filter/Arduino.h b/libraries/Filter/examples/Filter/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/Filter/examples/LowPassFilter/Arduino.h b/libraries/Filter/examples/LowPassFilter/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/GCS_Console/examples/Console/Arduino.h b/libraries/GCS_Console/examples/Console/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/PID/examples/pid/Arduino.h b/libraries/PID/examples/pid/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/libraries/RC_Channel/examples/RC_Channel/Arduino.h b/libraries/RC_Channel/examples/RC_Channel/Arduino.h deleted file mode 100644 index e69de29bb2..0000000000