diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 38ad1dee6b..9215be35d1 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -257,19 +257,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1; static AP_Baro barometer; -#if CONFIG_COMPASS == HAL_COMPASS_PX4 -static AP_Compass_PX4 compass; -#elif CONFIG_COMPASS == HAL_COMPASS_VRBRAIN -static AP_Compass_VRBRAIN compass; -#elif CONFIG_COMPASS == HAL_COMPASS_HMC5843 -static AP_Compass_HMC5843 compass; -#elif CONFIG_COMPASS == HAL_COMPASS_HIL -static AP_Compass_HIL compass; -#elif CONFIG_COMPASS == HAL_COMPASS_AK8963 -static AP_Compass_AK8963_MPU9250 compass; -#else - #error Unrecognized CONFIG_COMPASS setting -#endif +static Compass compass; AP_InertialSensor ins; diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 1bd6598250..5cbfca03f4 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -1031,12 +1031,6 @@ static void load_parameters(void) ahrs._kp_yaw.set_and_save(0.1); } - // setup different Compass learn setting for ArduCopter than the default - // but allow users to override in their config - if (!compass._learn.load()) { - compass._learn.set_and_save(0); - } - if (!g.format_version.load() || g.format_version != Parameters::k_format_version) { diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 1c5edab1a6..d43a24bc27 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -44,12 +44,6 @@ #error CONFIG_HAL_BOARD must be defined to build ArduCopter #endif -////////////////////////////////////////////////////////////////////////////// -// sensor types - -#define CONFIG_BARO HAL_BARO_DEFAULT -#define CONFIG_COMPASS HAL_COMPASS_DEFAULT - ////////////////////////////////////////////////////////////////////////////// // HIL_MODE OPTIONAL diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index ace519df84..b67615bf00 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -477,13 +477,13 @@ static void report_compass() // motor compensation cliSerial->print_P(PSTR("Motor Comp: ")); - if( compass.motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { + if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { cliSerial->print_P(PSTR("Off\n")); }else{ - if( compass.motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { + if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { cliSerial->print_P(PSTR("Throttle")); } - if( compass.motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { + if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { cliSerial->print_P(PSTR("Current")); } Vector3f motor_compensation;