Plane: use hal.util soft_armed state

This commit is contained in:
Jonathan Challinger 2015-01-28 15:30:00 -08:00 committed by Andrew Tridgell
parent 0cc83b1826
commit 4105edaa87
5 changed files with 6 additions and 6 deletions

View File

@ -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();
}

View File

@ -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()) {

View File

@ -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;
}

View File

@ -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++) {

View File

@ -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