diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index ec08f715b8..6553c586c7 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -583,7 +583,7 @@ void loop() // update AHRS system static void ahrs_update() { - ahrs.set_armed(hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); + hal.util->set_soft_armed(hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); #if HIL_MODE != HIL_MODE_DISABLED // update hil before AHRS update diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 453d9aff82..0c1df0fe18 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -75,7 +75,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/APMrover2/system.pde b/APMrover2/system.pde index 4dfb98c832..861d8d526d 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -489,7 +489,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