diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index f248317def..ca7152ca77 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -863,7 +863,7 @@ void loop() // update AHRS system static void ahrs_update() { - ahrs.set_armed(arming.is_armed() && + hal.util->set_soft_armed(arming.is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); #if HIL_MODE != HIL_MODE_DISABLED @@ -1157,7 +1157,7 @@ static void update_GPS_10Hz(void) } #endif - if (!ahrs.get_armed()) { + if (!hal.util->get_soft_armed()) { update_home(); } diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index a150513898..ed68b3d4d9 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -825,7 +825,7 @@ static void set_servos(void) min_throttle, max_throttle); - if (!ahrs.get_armed()) { + if (!hal.util->get_soft_armed()) { channel_throttle->servo_out = 0; channel_throttle->calc_pwm(); } else if (suppress_throttle()) { diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index c2b0f21c1d..cff778b065 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -86,7 +86,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan) #endif // we are armed if we are not initialising - if (control_mode != INITIALISING && ahrs.get_armed()) { + if (control_mode != INITIALISING && hal.util->get_soft_armed()) { base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; } diff --git a/ArduPlane/control_modes.pde b/ArduPlane/control_modes.pde index cfccebf96c..981a4134ef 100644 --- a/ArduPlane/control_modes.pde +++ b/ArduPlane/control_modes.pde @@ -68,7 +68,7 @@ static void read_control_switch() // we only update the mixer if we are not armed. This is // important as otherwise we will need to temporarily // disarm to change the mixer - if (ahrs.get_armed() || setup_failsafe_mixing()) { + if (hal.util->get_soft_armed() || setup_failsafe_mixing()) { px4io_override_enabled = true; // disable output channels to force PX4IO override for (uint8_t i=0; i<16; i++) { diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 0df4e09e1a..3aa2477e37 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -669,7 +669,7 @@ static bool should_log(uint32_t mask) if (!(mask & g.log_bitmask) || in_mavlink_delay) { return false; } - bool ret = ahrs.get_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0; + bool ret = hal.util->get_soft_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0; if (ret && !DataFlash.logging_started() && !in_log_download) { // we have to set in_mavlink_delay to prevent logging while // writing headers