mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: use AP_HAL_BOARD_DRIVER in remaining test sketches
This commit is contained in:
parent
4c715bfd04
commit
a1187519a8
|
@ -11,11 +11,7 @@
|
|||
#include <AP_Param.h>
|
||||
#include <AC_PID.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
// default PID values
|
||||
#define TEST_P 1.0
|
||||
|
|
|
@ -8,11 +8,7 @@
|
|||
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
void setup () {
|
||||
hal.console->println_P(PSTR("Unit test for APM_OBC. This sketch"
|
||||
|
|
|
@ -20,7 +20,7 @@ uint32_t timer;
|
|||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
/* Only build this sketch for APM1 */
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_ADC_ADS7844 adc;
|
||||
|
||||
|
|
|
@ -19,11 +19,7 @@
|
|||
#include <AP_Buffer.h>
|
||||
#include <AP_Airspeed.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
/* Build this example sketch only for the APM1. */
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_Baro_BMP085 bmp085;
|
||||
|
||||
|
|
|
@ -9,9 +9,9 @@
|
|||
#include <AP_Baro.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
||||
AP_Baro_MS5611 baro;
|
||||
static uint32_t timer;
|
||||
|
@ -58,7 +58,6 @@ void loop()
|
|||
|
||||
#else // Non-APM2
|
||||
#warning AP_Baro_MS5611_test built as stub for APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
void setup () {}
|
||||
void loop () {}
|
||||
#endif
|
||||
|
|
|
@ -13,11 +13,7 @@
|
|||
#include <AP_Declination.h>
|
||||
#include <AP_Compass.h> // Compass Library
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_Compass_HMC5843 compass;
|
||||
uint32_t timer;
|
||||
|
|
|
@ -11,11 +11,7 @@
|
|||
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
static const int16_t dec_tbl[37][73] = \
|
||||
{ \
|
||||
|
|
|
@ -21,19 +21,19 @@
|
|||
#include <AP_Buffer.h> // ArduPilot general purpose FIFO buffer
|
||||
|
||||
#include <AP_InertialNav.h>
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#define A_LED_PIN 27
|
||||
#define C_LED_PIN 25
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
AP_InertialSensor_MPU6000 ins;
|
||||
AP_Baro_MS5611 baro;
|
||||
|
||||
#else
|
||||
|
||||
#define A_LED_PIN 37
|
||||
#define C_LED_PIN 35
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
AP_ADC_ADS7844 adc;
|
||||
AP_InertialSensor_Oilpan ins(&adc);
|
||||
AP_Baro_BMP085 baro;
|
||||
|
|
|
@ -14,11 +14,7 @@
|
|||
|
||||
#include <AP_LeadFilter.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_LeadFilter xLeadFilter; // GPS lag filter
|
||||
|
||||
|
|
|
@ -11,11 +11,7 @@
|
|||
#include <AP_HAL.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
static float rad_diff(float rad1, float rad2)
|
||||
{
|
||||
|
|
|
@ -10,11 +10,7 @@
|
|||
#include <AP_Math.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
static const struct {
|
||||
Vector2f wp1, wp2, location;
|
||||
|
|
|
@ -10,11 +10,7 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
/*
|
||||
* this is the boundary of the 2010 outback challenge
|
||||
|
|
|
@ -11,11 +11,7 @@
|
|||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
// standard rotation matrices (these are the originals from the old code)
|
||||
#define MATRIX_ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0,0, 1)
|
||||
|
|
|
@ -8,11 +8,7 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
int8_t
|
||||
menu_test(uint8_t argc, const Menu::arg *argv)
|
||||
|
|
|
@ -14,11 +14,7 @@
|
|||
#include <AP_Curve.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
||||
|
||||
|
|
|
@ -21,11 +21,7 @@
|
|||
#include <AP_Mount.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
void setup () {
|
||||
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
|
||||
|
|
|
@ -12,11 +12,7 @@
|
|||
|
||||
#include <AP_OpticalFlow.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_OpticalFlow_ADNS3080 flowSensor;
|
||||
|
||||
|
|
|
@ -17,11 +17,11 @@
|
|||
#define HEAD_BYTE1 0xA3
|
||||
#define HEAD_BYTE2 0x95
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
DataFlash_APM2 DataFlash;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
DataFlash_APM1 DataFlash;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -13,11 +13,7 @@
|
|||
#include <DerivativeFilter.h>
|
||||
#include <AP_Buffer.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
#error Desktop build not supported with AP_HAL
|
||||
|
|
|
@ -15,11 +15,7 @@
|
|||
#include <AverageFilter.h> // AverageFilter class (inherits from Filter class)
|
||||
#include <AP_Buffer.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
||||
|
||||
|
|
|
@ -13,11 +13,7 @@
|
|||
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
|
||||
#include <AP_Buffer.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
// create a global instance of the class
|
||||
LowPassFilterFloat low_pass_filter;
|
||||
|
|
|
@ -18,11 +18,7 @@
|
|||
|
||||
#include "simplegcs.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
#endif
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
void flush_console_to_statustext() {
|
||||
uint8_t data[50];
|
||||
|
|
Loading…
Reference in New Issue