diff --git a/ArduCopter/AP_State.pde b/ArduCopter/AP_State.pde index 2217b4f677..b6d5f02045 100644 --- a/ArduCopter/AP_State.pde +++ b/ArduCopter/AP_State.pde @@ -127,3 +127,14 @@ void set_compass_healthy(bool b) } ap.compass_status = b; } + +// --------------------------------------------- + +void set_pre_arm_check(bool b) +{ + if(ap.pre_arm_check != b) { + ap.pre_arm_check = b; + AP_Notify::flags.pre_arm_check = b; + } +} + diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index f2a6786250..c61f58df1b 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -107,6 +107,7 @@ #include // main loop scheduler #include // RC input mapping library #include // ToshibaLED library +#include // ToshibaLED library // AP_HAL to Arduino compatibility layer #include "compat.h" @@ -150,7 +151,12 @@ static AP_Scheduler scheduler; static AP_BoardLED board_led; // Toshiba LED instance + #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 +static ToshibaLED_PX4 toshiba_led; + #else static ToshibaLED toshiba_led; + #endif + //////////////////////////////////////////////////////////////////////////////// // prototypes diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 434e169747..4a2322952d 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -295,7 +295,7 @@ static void auto_trim() auto_trim_counter--; // flash the leds - notify.flags.save_trim = true; + AP_Notify::flags.save_trim = true; // calculate roll trim adjustment float roll_trim_adjustment = ToRad((float)g.rc_1.control_in / 4000.0f); @@ -313,7 +313,7 @@ static void auto_trim() // on last iteration restore leds and accel gains to normal if(auto_trim_counter == 0) { ahrs.set_fast_gains(false); - notify.flags.save_trim = false; + AP_Notify::flags.save_trim = false; } } } diff --git a/ArduCopter/leds.pde b/ArduCopter/leds.pde index 1af7932786..d46edba14c 100644 --- a/ArduCopter/leds.pde +++ b/ArduCopter/leds.pde @@ -4,7 +4,7 @@ // should be called at 50hz ~ 100hz static void update_toshiba_led() { - toshiba_led.update(); + AP_Notify::update(); } ///////////////////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index e94f755dff..9d2b2c5f3b 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -217,7 +217,7 @@ static void pre_arm_checks(bool display_failure) // succeed if pre arm checks are disabled if(!g.arming_check_enabled) { - ap.pre_arm_check = true; + set_pre_arm_check(true); return; } @@ -328,7 +328,7 @@ static void pre_arm_checks(bool display_failure) } // if we've gotten this far then pre arm checks have completed - ap.pre_arm_check = true; + set_pre_arm_check(true); } // perform pre_arm_rc_checks checks and set ap.pre_arm_rc_check flag diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 9d21f890e6..9f35621416 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -75,7 +75,7 @@ static void init_rc_out() // display message on console cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n")); // turn on esc calibration notification - notify.flags.esc_calibration = true; + AP_Notify::flags.esc_calibration = true; // block until we restart while(1) {} }else{ diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 8fa6a7674a..729ea62f54 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -1356,7 +1356,7 @@ init_esc() while(1) { read_radio(); delay(100); - notify.flags.esc_calibration = true; + AP_Notify::flags.esc_calibration = true; motors.throttle_pass_through(); } }