From 0cc31c2db5da8db765dd53404aeb1cd2c7eb56de Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 1 Jun 2015 16:58:11 +1000 Subject: [PATCH] AP_HAL_AVR: convert example from .pde to .cpp --- ...{ArduCopterLibs.pde => ArduCopterLibs.cpp} | 0 .../examples/ArduCopterLibs/make.inc | 38 +++++++++++++++++++ .../{ArduPlaneLibs.pde => ArduPlaneLibs.cpp} | 0 .../examples/ArduPlaneLibs/make.inc | 34 +++++++++++++++++ .../examples/Blink/{Blink.pde => Blink.cpp} | 0 libraries/AP_HAL_AVR/examples/Blink/make.inc | 7 ++++ .../Console/{Console.pde => Console.cpp} | 0 .../AP_HAL_AVR/examples/Console/make.inc | 7 ++++ ...er_HMC5883L.pde => I2CDriver_HMC5883L.cpp} | 0 .../examples/I2CDriver_HMC5883L/make.inc | 7 ++++ .../LCDTest/{LCDTest.pde => LCDTest.cpp} | 0 .../AP_HAL_AVR/examples/LCDTest/make.inc | 6 +++ .../{RCInputTest.pde => RCInputTest.cpp} | 0 .../AP_HAL_AVR/examples/RCInputTest/make.inc | 7 ++++ .../{RCJitterTest.pde => RCJitterTest.cpp} | 0 .../AP_HAL_AVR/examples/RCJitterTest/make.inc | 7 ++++ ...sthroughTest.pde => RCPassthroughTest.cpp} | 0 .../examples/RCPassthroughTest/make.inc | 7 ++++ ...iver_MPU6000.pde => SPIDriver_MPU6000.cpp} | 0 .../examples/SPIDriver_MPU6000/make.inc | 7 ++++ .../{Scheduler.pde => Scheduler.cpp} | 0 .../AP_HAL_AVR/examples/Scheduler/make.inc | 6 +++ .../{Semaphore.pde => Semaphore.cpp} | 0 .../AP_HAL_AVR/examples/Semaphore/make.inc | 6 +++ .../Storage/{Storage.pde => Storage.cpp} | 0 .../AP_HAL_AVR/examples/Storage/make.inc | 7 ++++ .../{UARTDriver.pde => UARTDriver.cpp} | 0 .../AP_HAL_AVR/examples/UARTDriver/make.inc | 7 ++++ ...tyStringTest.pde => UtilityStringTest.cpp} | 0 .../examples/UtilityStringTest/make.inc | 7 ++++ 30 files changed, 160 insertions(+) rename libraries/AP_HAL_AVR/examples/ArduCopterLibs/{ArduCopterLibs.pde => ArduCopterLibs.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc rename libraries/AP_HAL_AVR/examples/ArduPlaneLibs/{ArduPlaneLibs.pde => ArduPlaneLibs.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc rename libraries/AP_HAL_AVR/examples/Blink/{Blink.pde => Blink.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/Blink/make.inc rename libraries/AP_HAL_AVR/examples/Console/{Console.pde => Console.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/Console/make.inc rename libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/{I2CDriver_HMC5883L.pde => I2CDriver_HMC5883L.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc rename libraries/AP_HAL_AVR/examples/LCDTest/{LCDTest.pde => LCDTest.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/LCDTest/make.inc rename libraries/AP_HAL_AVR/examples/RCInputTest/{RCInputTest.pde => RCInputTest.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/RCInputTest/make.inc rename libraries/AP_HAL_AVR/examples/RCJitterTest/{RCJitterTest.pde => RCJitterTest.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc rename libraries/AP_HAL_AVR/examples/RCPassthroughTest/{RCPassthroughTest.pde => RCPassthroughTest.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc rename libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/{SPIDriver_MPU6000.pde => SPIDriver_MPU6000.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc rename libraries/AP_HAL_AVR/examples/Scheduler/{Scheduler.pde => Scheduler.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/Scheduler/make.inc rename libraries/AP_HAL_AVR/examples/Semaphore/{Semaphore.pde => Semaphore.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/Semaphore/make.inc rename libraries/AP_HAL_AVR/examples/Storage/{Storage.pde => Storage.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/Storage/make.inc rename libraries/AP_HAL_AVR/examples/UARTDriver/{UARTDriver.pde => UARTDriver.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/UARTDriver/make.inc rename libraries/AP_HAL_AVR/examples/UtilityStringTest/{UtilityStringTest.pde => UtilityStringTest.cpp} (100%) create mode 100644 libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc diff --git a/libraries/AP_HAL_AVR/examples/ArduCopterLibs/ArduCopterLibs.pde b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/ArduCopterLibs.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/ArduCopterLibs/ArduCopterLibs.pde rename to libraries/AP_HAL_AVR/examples/ArduCopterLibs/ArduCopterLibs.cpp diff --git a/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc new file mode 100644 index 0000000000..8179acdfeb --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/ArduCopterLibs/make.inc @@ -0,0 +1,38 @@ +LIBRARIES += AC_PID +LIBRARIES += AP_ADC +LIBRARIES += AP_ADC_AnalogSource +LIBRARIES += AP_AHRS +LIBRARIES += AP_Airspeed +LIBRARIES += AP_Baro +LIBRARIES += AP_BattMonitor +LIBRARIES += AP_Buffer +LIBRARIES += AP_Camera +LIBRARIES += AP_Common +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 +LIBRARIES += AP_Menu +LIBRARIES += AP_Mission +LIBRARIES += AP_Motors +LIBRARIES += AP_Mount +LIBRARIES += AP_NavEKF +LIBRARIES += AP_Notify +LIBRARIES += AP_OpticalFlow +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += AP_RangeFinder +LIBRARIES += AP_Relay +LIBRARIES += AP_Terrain +LIBRARIES += AP_Vehicle +LIBRARIES += DataFlash +LIBRARIES += Filter +LIBRARIES += GCS_MAVLink +LIBRARIES += memcheck +LIBRARIES += RC_Channel +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/ArduPlaneLibs.pde b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/ArduPlaneLibs.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/ArduPlaneLibs/ArduPlaneLibs.pde rename to libraries/AP_HAL_AVR/examples/ArduPlaneLibs/ArduPlaneLibs.cpp diff --git a/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc new file mode 100644 index 0000000000..03bc15acf9 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/ArduPlaneLibs/make.inc @@ -0,0 +1,34 @@ +LIBRARIES += AP_ADC +LIBRARIES += AP_ADC_AnalogSource +LIBRARIES += AP_AHRS +LIBRARIES += AP_Airspeed +LIBRARIES += AP_Baro +LIBRARIES += AP_BattMonitor +LIBRARIES += AP_Buffer +LIBRARIES += AP_Camera +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 +LIBRARIES += AP_Menu +LIBRARIES += AP_Mission +LIBRARIES += AP_Mount +LIBRARIES += AP_Notify +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += AP_RangeFinder +LIBRARIES += AP_Relay +LIBRARIES += AP_Terrain +LIBRARIES += AP_Vehicle +LIBRARIES += DataFlash +LIBRARIES += Filter +LIBRARIES += GCS_MAVLink +LIBRARIES += memcheck +LIBRARIES += PID +LIBRARIES += RC_Channel +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/Blink/Blink.pde b/libraries/AP_HAL_AVR/examples/Blink/Blink.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/Blink/Blink.pde rename to libraries/AP_HAL_AVR/examples/Blink/Blink.cpp diff --git a/libraries/AP_HAL_AVR/examples/Blink/make.inc b/libraries/AP_HAL_AVR/examples/Blink/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/Blink/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/Console/Console.pde b/libraries/AP_HAL_AVR/examples/Console/Console.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/Console/Console.pde rename to libraries/AP_HAL_AVR/examples/Console/Console.cpp diff --git a/libraries/AP_HAL_AVR/examples/Console/make.inc b/libraries/AP_HAL_AVR/examples/Console/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/Console/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde rename to libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp diff --git a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/LCDTest/LCDTest.pde b/libraries/AP_HAL_AVR/examples/LCDTest/LCDTest.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/LCDTest/LCDTest.pde rename to libraries/AP_HAL_AVR/examples/LCDTest/LCDTest.cpp diff --git a/libraries/AP_HAL_AVR/examples/LCDTest/make.inc b/libraries/AP_HAL_AVR/examples/LCDTest/make.inc new file mode 100644 index 0000000000..b454167fdd --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/LCDTest/make.inc @@ -0,0 +1,6 @@ +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/RCInputTest.pde b/libraries/AP_HAL_AVR/examples/RCInputTest/RCInputTest.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/RCInputTest/RCInputTest.pde rename to libraries/AP_HAL_AVR/examples/RCInputTest/RCInputTest.cpp diff --git a/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc b/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/RCInputTest/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/RCJitterTest/RCJitterTest.pde b/libraries/AP_HAL_AVR/examples/RCJitterTest/RCJitterTest.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/RCJitterTest/RCJitterTest.pde rename to libraries/AP_HAL_AVR/examples/RCJitterTest/RCJitterTest.cpp diff --git a/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc b/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/RCJitterTest/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde rename to libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.cpp diff --git a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/SPIDriver_MPU6000.pde b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/SPIDriver_MPU6000.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/SPIDriver_MPU6000.pde rename to libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/SPIDriver_MPU6000.cpp diff --git a/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/SPIDriver_MPU6000/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/Scheduler/Scheduler.pde b/libraries/AP_HAL_AVR/examples/Scheduler/Scheduler.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/Scheduler/Scheduler.pde rename to libraries/AP_HAL_AVR/examples/Scheduler/Scheduler.cpp diff --git a/libraries/AP_HAL_AVR/examples/Scheduler/make.inc b/libraries/AP_HAL_AVR/examples/Scheduler/make.inc new file mode 100644 index 0000000000..b454167fdd --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/Scheduler/make.inc @@ -0,0 +1,6 @@ +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/Semaphore.pde b/libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.pde rename to libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp diff --git a/libraries/AP_HAL_AVR/examples/Semaphore/make.inc b/libraries/AP_HAL_AVR/examples/Semaphore/make.inc new file mode 100644 index 0000000000..b454167fdd --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/Semaphore/make.inc @@ -0,0 +1,6 @@ +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/Storage.pde b/libraries/AP_HAL_AVR/examples/Storage/Storage.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/Storage/Storage.pde rename to libraries/AP_HAL_AVR/examples/Storage/Storage.cpp diff --git a/libraries/AP_HAL_AVR/examples/Storage/make.inc b/libraries/AP_HAL_AVR/examples/Storage/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/Storage/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/UARTDriver/UARTDriver.pde b/libraries/AP_HAL_AVR/examples/UARTDriver/UARTDriver.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/UARTDriver/UARTDriver.pde rename to libraries/AP_HAL_AVR/examples/UARTDriver/UARTDriver.cpp diff --git a/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc b/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/UARTDriver/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager diff --git a/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.pde b/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp similarity index 100% rename from libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.pde rename to libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp diff --git a/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc b/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc new file mode 100644 index 0000000000..89315e2830 --- /dev/null +++ b/libraries/AP_HAL_AVR/examples/UtilityStringTest/make.inc @@ -0,0 +1,7 @@ +LIBRARIES += AP_Common +LIBRARIES += AP_HAL +LIBRARIES += AP_HAL_AVR +LIBRARIES += AP_Math +LIBRARIES += AP_Param +LIBRARIES += AP_Progmem +LIBRARIES += StorageManager