CONFIG_HAL_BOARD - test sketches fixed up, build all passes
This commit is contained in:
parent
25e597d3b3
commit
475da4eca4
@ -11,7 +11,11 @@
|
|||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
#include <AC_PID.h>
|
#include <AC_PID.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
// default PID values
|
// default PID values
|
||||||
#define TEST_P 1.0
|
#define TEST_P 1.0
|
||||||
|
@ -7,7 +7,12 @@
|
|||||||
#include <APM_OBC.h>
|
#include <APM_OBC.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
void setup () {
|
void setup () {
|
||||||
hal.console->println_P(PSTR("Unit test for APM_OBC. This sketch"
|
hal.console->println_P(PSTR("Unit test for APM_OBC. This sketch"
|
||||||
|
@ -7,12 +7,17 @@
|
|||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
#include <AP_ADC.h>
|
#include <AP_ADC.h>
|
||||||
|
|
||||||
|
#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_AVR_APM1;
|
||||||
|
|
||||||
AP_ADC_ADS7844 adc;
|
AP_ADC_ADS7844 adc;
|
||||||
@ -67,7 +72,7 @@ static void show_data()
|
|||||||
/* clearly out of bounds values: */
|
/* clearly out of bounds values: */
|
||||||
min[i] = 99999999.0f;
|
min[i] = 99999999.0f;
|
||||||
max[i] = -88888888.0f;
|
max[i] = -88888888.0f;
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
do {
|
do {
|
||||||
@ -101,4 +106,11 @@ void loop()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#else // Non-APM1:
|
||||||
|
#warning AP_ADC_test built as stub for APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
|
void setup () {}
|
||||||
|
void loop () {}
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
@ -23,13 +23,10 @@
|
|||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
/* Only testing with APM2 for now. */
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
#define APM2_HARDWARE
|
|
||||||
|
|
||||||
#ifdef APM2_HARDWARE
|
|
||||||
AP_InertialSensor_MPU6000 ins;
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
# else
|
AP_InertialSensor_MPU6000 ins;
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
AP_ADC_ADS7844 adc;
|
AP_ADC_ADS7844 adc;
|
||||||
AP_InertialSensor_Oilpan ins( &adc );
|
AP_InertialSensor_Oilpan ins( &adc );
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
@ -51,7 +48,7 @@ AP_Baro_BMP085_HIL barometer;
|
|||||||
#define HIGH 1
|
#define HIGH 1
|
||||||
#define LOW 0
|
#define LOW 0
|
||||||
|
|
||||||
#ifdef APM2_HARDWARE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
# define A_LED_PIN 27
|
# define A_LED_PIN 27
|
||||||
# define C_LED_PIN 25
|
# define C_LED_PIN 25
|
||||||
# define LED_ON LOW
|
# define LED_ON LOW
|
||||||
|
@ -19,7 +19,11 @@
|
|||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
#include <AP_Airspeed.h>
|
#include <AP_Airspeed.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_Airspeed airspeed;
|
AP_Airspeed airspeed;
|
||||||
|
|
||||||
|
@ -18,6 +18,8 @@
|
|||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#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_AVR_APM1;
|
||||||
|
|
||||||
AP_Baro_BMP085 bmp085(0);
|
AP_Baro_BMP085 bmp085(0);
|
||||||
@ -65,4 +67,11 @@ void loop()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#else // Non-APM1
|
||||||
|
#warning AP_Baro_BMP085_test built as stub for APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
|
void setup() {}
|
||||||
|
void loop() {}
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
@ -4,14 +4,15 @@
|
|||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
|
||||||
|
|
||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
#include <Filter.h>
|
#include <Filter.h>
|
||||||
#include <AP_Baro.h>
|
#include <AP_Baro.h>
|
||||||
|
|
||||||
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
|
|
||||||
AP_Baro_MS5611 baro;
|
AP_Baro_MS5611 baro;
|
||||||
static uint32_t timer;
|
static uint32_t timer;
|
||||||
|
|
||||||
@ -55,4 +56,11 @@ 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
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
#include <AP_Declination.h>
|
#include <AP_Declination.h>
|
||||||
#include <AP_Compass.h> // Compass Library
|
#include <AP_Compass.h> // Compass Library
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_Compass_HMC5843 compass;
|
AP_Compass_HMC5843 compass;
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
@ -10,7 +10,12 @@
|
|||||||
#include <Filter.h>
|
#include <Filter.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
static const int16_t dec_tbl[37][73] = \
|
static const int16_t dec_tbl[37][73] = \
|
||||||
{ \
|
{ \
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
GPS *gps;
|
GPS *gps;
|
||||||
AP_GPS_Auto GPS(hal.uartB, &gps);
|
AP_GPS_Auto GPS(hal.uartB, &gps);
|
||||||
|
@ -15,7 +15,11 @@
|
|||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_GPS_MTK16 gps(hal.uartB);
|
AP_GPS_MTK16 gps(hal.uartB);
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
|
@ -15,7 +15,11 @@
|
|||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_GPS_UBLOX gps(hal.uartB);
|
AP_GPS_UBLOX gps(hal.uartB);
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
|
@ -1,10 +1,17 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_HAL::AnalogSource* ch0;
|
AP_HAL::AnalogSource* ch0;
|
||||||
AP_HAL::AnalogSource* ch1;
|
AP_HAL::AnalogSource* ch1;
|
||||||
|
@ -35,7 +35,11 @@
|
|||||||
#include <GCS_MAVLink.h>
|
#include <GCS_MAVLink.h>
|
||||||
#include <memcheck.h>
|
#include <memcheck.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
|
|
||||||
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
||||||
|
@ -30,7 +30,11 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
|
|
||||||
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
||||||
|
@ -7,12 +7,18 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.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;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#endif
|
||||||
|
|
||||||
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
void stream_loopback(AP_HAL::Stream* s, uint32_t time) {
|
||||||
uint32_t end = hal.scheduler->millis() + time;
|
uint32_t end = hal.scheduler->millis() + time;
|
||||||
|
@ -5,11 +5,18 @@
|
|||||||
*******************************************/
|
*******************************************/
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
const AP_HAL_AVR::HAL_AVR& hal = AP_HAL_AVR_APM2;
|
#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
|
||||||
|
|
||||||
#define HMC5883L 0x1E
|
#define HMC5883L 0x1E
|
||||||
|
|
||||||
|
@ -38,13 +38,20 @@
|
|||||||
// include the library code:
|
// include the library code:
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
#include "LCrystal.h"
|
#include "LCrystal.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;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#endif
|
||||||
|
|
||||||
// initialize the library with the numbers of the interface pins
|
// initialize the library with the numbers of the interface pins
|
||||||
LiquidCrystal lcd(8, 9, 4, 5, 6, 7);
|
LiquidCrystal lcd(8, 9, 4, 5, 6, 7);
|
||||||
|
@ -1,10 +1,17 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
void multiread(AP_HAL::RCInput* in) {
|
void multiread(AP_HAL::RCInput* in) {
|
||||||
/* Multi-channel read method: */
|
/* Multi-channel read method: */
|
||||||
|
@ -1,10 +1,17 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
||||||
/* Multi-channel read method: */
|
/* Multi-channel read method: */
|
||||||
|
@ -5,7 +5,10 @@
|
|||||||
*******************************************/
|
*******************************************/
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
@ -15,9 +18,11 @@
|
|||||||
// debug only:
|
// debug only:
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
|
||||||
const AP_HAL_AVR::HAL_AVR& hal = AP_HAL_AVR_APM2;
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
const uint8_t _baro_cs_pin = 40;
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_HAL::SPIDeviceDriver* spidev;
|
AP_HAL::SPIDeviceDriver* spidev;
|
||||||
|
|
||||||
@ -110,17 +115,6 @@ static void setup() {
|
|||||||
hal.console->printf_P(PSTR("Initializing MPU6000\r\n"));
|
hal.console->printf_P(PSTR("Initializing MPU6000\r\n"));
|
||||||
spidev = hal.spi->device(AP_HAL::SPIDevice_MPU6000);
|
spidev = hal.spi->device(AP_HAL::SPIDevice_MPU6000);
|
||||||
|
|
||||||
#if 0
|
|
||||||
/* Setup the barometer cs to stop it from holding the bus */
|
|
||||||
hal.gpio->pinMode(_baro_cs_pin, GPIO_OUTPUT);
|
|
||||||
hal.gpio->write(_baro_cs_pin, 1);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
spidev->cs_assert();
|
|
||||||
uint8_t spcr = SPCR;
|
|
||||||
uint8_t spsr = SPSR;
|
|
||||||
spidev->cs_release();
|
|
||||||
|
|
||||||
mpu6k_init();
|
mpu6k_init();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,10 +1,17 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You'll want to use a logic analyzer to watch the effects of this test.
|
* You'll want to use a logic analyzer to watch the effects of this test.
|
||||||
|
@ -1,10 +1,17 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.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;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t fibs[12] = { 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144 };
|
uint8_t fibs[12] = { 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144 };
|
||||||
|
|
||||||
|
@ -7,11 +7,18 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.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;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#endif
|
||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
|
@ -14,13 +14,7 @@
|
|||||||
#include <AP_ADC.h>
|
#include <AP_ADC.h>
|
||||||
#include <AP_InertialSensor.h>
|
#include <AP_InertialSensor.h>
|
||||||
|
|
||||||
#define APM_HARDWARE_APM1 1
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
#define APM_HARDWARE_APM2 2
|
|
||||||
|
|
||||||
#define CONFIG_APM_HARDWARE APM_HARDWARE_APM2
|
|
||||||
//#define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
|
|
||||||
|
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
|
||||||
#define SAMPLE_UNIT 1
|
#define SAMPLE_UNIT 1
|
||||||
#define A_LED_PIN 27
|
#define A_LED_PIN 27
|
||||||
#define C_LED_PIN 25
|
#define C_LED_PIN 25
|
||||||
@ -32,7 +26,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
AP_InertialSensor_MPU6000 ins;
|
AP_InertialSensor_MPU6000 ins;
|
||||||
@ -57,13 +51,13 @@ void setup(void)
|
|||||||
hal.gpio->pinMode(A_LED_PIN, GPIO_OUTPUT);
|
hal.gpio->pinMode(A_LED_PIN, GPIO_OUTPUT);
|
||||||
hal.gpio->pinMode(C_LED_PIN, GPIO_OUTPUT);
|
hal.gpio->pinMode(C_LED_PIN, GPIO_OUTPUT);
|
||||||
|
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
// we need to stop the barometer from holding the SPI bus
|
// we need to stop the barometer from holding the SPI bus
|
||||||
hal.gpio->pinMode(40, GPIO_OUTPUT);
|
hal.gpio->pinMode(40, GPIO_OUTPUT);
|
||||||
hal.gpio->write(40, 1);
|
hal.gpio->write(40, 1);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
adc.Init(&scheduler); // APM ADC library initialization
|
adc.Init(&scheduler); // APM ADC library initialization
|
||||||
#endif
|
#endif
|
||||||
ins.init(AP_InertialSensor::COLD_START,
|
ins.init(AP_InertialSensor::COLD_START,
|
||||||
|
@ -14,7 +14,11 @@
|
|||||||
|
|
||||||
#include <AP_LeadFilter.h>
|
#include <AP_LeadFilter.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_LeadFilter xLeadFilter; // GPS lag filter
|
AP_LeadFilter xLeadFilter; // GPS lag filter
|
||||||
|
|
||||||
|
@ -11,7 +11,11 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
static float rad_diff(float rad1, float rad2)
|
static float rad_diff(float rad1, float rad2)
|
||||||
{
|
{
|
||||||
|
@ -10,7 +10,11 @@
|
|||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
static const struct {
|
static const struct {
|
||||||
Vector2f wp1, wp2, location;
|
Vector2f wp1, wp2, location;
|
||||||
|
@ -10,7 +10,11 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* this is the boundary of the 2010 outback challenge
|
* this is the boundary of the 2010 outback challenge
|
||||||
|
@ -11,7 +11,11 @@
|
|||||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
// standard rotation matrices (these are the originals from the old code)
|
// 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)
|
#define MATRIX_ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0,0, 1)
|
||||||
|
@ -1,11 +1,18 @@
|
|||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem.h>
|
||||||
|
|
||||||
#include <AP_Menu.h>
|
#include <AP_Menu.h>
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
int8_t
|
int8_t
|
||||||
menu_test(uint8_t argc, const Menu::arg *argv)
|
menu_test(uint8_t argc, const Menu::arg *argv)
|
||||||
|
@ -14,7 +14,11 @@
|
|||||||
#include <AP_Curve.h>
|
#include <AP_Curve.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
||||||
|
|
||||||
|
@ -21,7 +21,11 @@
|
|||||||
#include <AP_Mount.h>
|
#include <AP_Mount.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
void setup () {
|
void setup () {
|
||||||
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
|
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
|
||||||
|
@ -12,7 +12,11 @@
|
|||||||
|
|
||||||
#include <AP_OpticalFlow.h>
|
#include <AP_OpticalFlow.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
AP_OpticalFlow_ADNS3080 flowSensor;
|
AP_OpticalFlow_ADNS3080 flowSensor;
|
||||||
|
|
||||||
|
@ -15,13 +15,6 @@
|
|||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
|
||||||
#define APM_HARDWARE_APM1 1
|
|
||||||
#define APM_HARDWARE_APM2 2
|
|
||||||
|
|
||||||
// uncomment appropriate line for your APM hardware type
|
|
||||||
//#define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
|
|
||||||
#define CONFIG_APM_HARDWARE APM_HARDWARE_APM2 // also applies to APM2.5
|
|
||||||
|
|
||||||
// uncomment appropriate line corresponding to your sonar
|
// uncomment appropriate line corresponding to your sonar
|
||||||
#define SONAR_TYPE AP_RANGEFINDER_MAXSONARXL // 0 - XL (default)
|
#define SONAR_TYPE AP_RANGEFINDER_MAXSONARXL // 0 - XL (default)
|
||||||
//#define SONAR_TYPE AP_RANGEFINDER_MAXSONARLV // 1 - LV (cheaper)
|
//#define SONAR_TYPE AP_RANGEFINDER_MAXSONARLV // 1 - LV (cheaper)
|
||||||
@ -30,7 +23,7 @@
|
|||||||
//#define SONAR_TYPE AP_RANGEFINDER_MAXSONARI2CXL // 4 - XLI2C (XL with I2C interface and 7m range)
|
//#define SONAR_TYPE AP_RANGEFINDER_MAXSONARI2CXL // 4 - XLI2C (XL with I2C interface and 7m range)
|
||||||
|
|
||||||
// For APM1 we use built in ADC for sonar reads from an analog pin
|
// For APM1 we use built in ADC for sonar reads from an analog pin
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 && SONAR_TYPE <= AP_RANGEFINDER_MAXSONARHRLV
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 && SONAR_TYPE <= AP_RANGEFINDER_MAXSONARHRLV
|
||||||
# define USE_ADC_ADS7844 // use APM1's built in ADC and connect sonar to pitot tube
|
# define USE_ADC_ADS7844 // use APM1's built in ADC and connect sonar to pitot tube
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -42,7 +35,7 @@
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 // also applies to APM2.5
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
#else
|
#else
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
#include <DerivativeFilter.h>
|
#include <DerivativeFilter.h>
|
||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
#ifdef DESKTOP_BUILD
|
#ifdef DESKTOP_BUILD
|
||||||
#error Desktop build not supported with AP_HAL
|
#error Desktop build not supported with AP_HAL
|
||||||
|
@ -15,7 +15,11 @@
|
|||||||
#include <AverageFilter.h> // AverageFilter class (inherits from Filter class)
|
#include <AverageFilter.h> // AverageFilter class (inherits from Filter class)
|
||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
||||||
|
|
||||||
|
@ -13,7 +13,11 @@
|
|||||||
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
|
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
|
||||||
#include <AP_Buffer.h>
|
#include <AP_Buffer.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
// create a global instance of the class
|
// create a global instance of the class
|
||||||
LowPassFilterFloat low_pass_filter;
|
LowPassFilterFloat low_pass_filter;
|
||||||
|
@ -18,7 +18,11 @@
|
|||||||
|
|
||||||
#include "simplegcs.h"
|
#include "simplegcs.h"
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
void flush_console_to_statustext() {
|
void flush_console_to_statustext() {
|
||||||
uint8_t data[50];
|
uint8_t data[50];
|
||||||
|
@ -21,7 +21,11 @@
|
|||||||
#include <RC_Channel.h>
|
#include <RC_Channel.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
const AP_HAL::HAL& hal = AP_HAL_AVR_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
|
||||||
|
|
||||||
RC_Channel rc_1(CH_1);
|
RC_Channel rc_1(CH_1);
|
||||||
RC_Channel rc_2(CH_2);
|
RC_Channel rc_2(CH_2);
|
||||||
|
Loading…
Reference in New Issue
Block a user