APMrover2: use hal.util soft_armed state

This commit is contained in:
Jonathan Challinger 2015-01-28 15:44:50 -08:00 committed by Andrew Tridgell
parent 4105edaa87
commit d08aa3edac
3 changed files with 3 additions and 3 deletions

View File

@ -583,7 +583,7 @@ void loop()
// update AHRS system // update AHRS system
static void ahrs_update() 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 #if HIL_MODE != HIL_MODE_DISABLED
// update hil before AHRS update // update hil before AHRS update

View File

@ -75,7 +75,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
#endif #endif
// we are armed if we are not initialising // 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; base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
} }

View File

@ -489,7 +489,7 @@ static bool should_log(uint32_t mask)
if (!(mask & g.log_bitmask) || in_mavlink_delay) { if (!(mask & g.log_bitmask) || in_mavlink_delay) {
return false; 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) { if (ret && !DataFlash.logging_started() && !in_log_download) {
// we have to set in_mavlink_delay to prevent logging while // we have to set in_mavlink_delay to prevent logging while
// writing headers // writing headers