diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 5c60557217..e470d74eac 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -4,13 +4,9 @@ // you wish to change any of the setup parameters from their default // values, place the appropriate #define statements here. -//#define CONFIG_APM_HARDWARE APM_HARDWARE_APM2 - -// Ordinary users should please ignore the following define. -// APM2_BETA_HARDWARE is used to support early (September-October 2011) APM2 -// hardware which had the BMP085 barometer onboard. Only a handful of -// developers have these boards. -//#define APM2_BETA_HARDWARE +// If you used to define your CONFIG_APM_HARDWARE setting here, it is no +// longer valid! You should switch to using CONFIG_HAL_BOARD via the HAL_BOARD +// flag in your local config.mk instead. // The following are the recommended settings for Xplane // simulation. Remove the leading "/* and trailing "*/" to enable: diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 8428995336..6ea29e14eb 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -72,7 +72,7 @@ AP_HAL::BetterStream* cliSerial; -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; #else const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; @@ -116,7 +116,7 @@ static void update_events(void); //////////////////////////////////////////////////////////////////////////////// // DataFlash //////////////////////////////////////////////////////////////////////////////// -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 DataFlash_APM2 DataFlash; #else DataFlash_APM1 DataFlash; @@ -155,7 +155,7 @@ SITL sitl; #else #if CONFIG_BARO == AP_BARO_BMP085 - # if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 + # if CONFIG_HAL_BOARD == HAL_BOARD_APM2 static AP_Baro_BMP085 barometer(true); # else static AP_Baro_BMP085 barometer(false); @@ -920,7 +920,7 @@ static void slow_loop() case 1: slow_loopCounter++; -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); #else update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11); diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index cf4b328dd0..272b5b7ee0 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -512,7 +512,7 @@ static void set_servos(void) g.rc_6.output_ch(CH_6); g.rc_7.output_ch(CH_7); g.rc_8.output_ch(CH_8); - # if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1 + # if CONFIG_HAL_BOARD == HAL_BOARD_APM2 g.rc_9.output_ch(CH_9); g.rc_10.output_ch(CH_10); g.rc_11.output_ch(CH_11); diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 5230d21819..891320f092 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -368,7 +368,7 @@ public: RC_Channel_aux rc_6; RC_Channel_aux rc_7; RC_Channel_aux rc_8; -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 RC_Channel_aux rc_9; RC_Channel_aux rc_10; RC_Channel_aux rc_11; @@ -403,7 +403,7 @@ public: rc_6 (CH_6), rc_7 (CH_7), rc_8 (CH_8), -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 rc_9 (CH_9), rc_10 (CH_10), rc_11 (CH_11), diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 963bf863ef..637c16c16a 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -622,7 +622,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp, ../libraries/RC_Channel/RC_Channel.cpp GGROUP(rc_8, "RC8_", RC_Channel_aux), -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 // @Group: RC9_ // @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp, ../libraries/RC_Channel/RC_Channel.cpp GGROUP(rc_9, "RC9_", RC_Channel_aux), diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 15b9b242da..52528a93d7 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -50,14 +50,14 @@ ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// +#ifdef CONFIG_APM_HARDWARE +#error CONFIG_APM_HARDWARE option is depreated! use CONFIG_HAL_BOARD instead. +#endif + ////////////////////////////////////////////////////////////////////////////// // APM HARDWARE // -#ifndef CONFIG_APM_HARDWARE - # define CONFIG_APM_HARDWARE APM_HARDWARE_APM1 -#endif - #if defined( __AVR_ATmega1280__ ) // default choices for a 1280. We can't fit everything in, so we // make some popular choices @@ -86,7 +86,7 @@ // APM2 HARDWARE DEFAULTS // -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 # define CONFIG_INS_TYPE CONFIG_INS_MPU6000 # define CONFIG_RELAY DISABLED # define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD @@ -108,7 +108,7 @@ ////////////////////////////////////////////////////////////////////////////// // LED and IO Pins // -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 # define A_LED_PIN 37 # define B_LED_PIN 36 # define C_LED_PIN 35 @@ -118,7 +118,7 @@ # define CONFIG_RELAY ENABLED # define BATTERY_VOLT_PIN 0 // Battery voltage on A0 # define BATTERY_CURR_PIN 1 // Battery current on A1 -#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 +#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 # define A_LED_PIN 27 # define B_LED_PIN 26 # define C_LED_PIN 25 diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 0d96fc7368..4b2b7f30a7 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -225,9 +225,6 @@ enum gcs_severity { #define CONFIG_INS_OILPAN 1 #define CONFIG_INS_MPU6000 2 -#define APM_HARDWARE_APM1 1 -#define APM_HARDWARE_APM2 2 - #define AP_BARO_BMP085 1 #define AP_BARO_MS5611 2 diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 2cddb7917a..730e788dff 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -36,10 +36,10 @@ static void init_rc_in() rc_ch[CH_8] = &g.rc_8; //set auxiliary ranges -#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 - update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); -#else +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11); +#else + update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); #endif } @@ -62,7 +62,7 @@ static void init_rc_out() hal.rcout->write(CH_7, g.rc_7.radio_trim); hal.rcout->write(CH_8, g.rc_8.radio_trim); -#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1 +#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 hal.rcout->write(CH_9, g.rc_9.radio_trim); hal.rcout->write(CH_10, g.rc_10.radio_trim); hal.rcout->write(CH_11, g.rc_11.radio_trim);