diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index fa175a82e5..8795e83f45 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -125,6 +125,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) init_rc_out(); enable_motor_output(); motors->armed(true); + hal.util->set_soft_armed(true); // initialise run time last_run_time = millis(); @@ -230,6 +231,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) // stop motors motors->output_min(); motors->armed(false); + hal.util->set_soft_armed(false); // set and save motor compensation if (updated) { diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 9c5dc0ba1f..c403852b3c 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -41,6 +41,7 @@ void Copter::motor_test_output() motor_test_start_ms = now; if (!motors->armed()) { motors->armed(true); + hal.util->set_soft_armed(true); } } return; @@ -152,6 +153,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t init_rc_out(); enable_motor_output(); motors->armed(true); + hal.util->set_soft_armed(true); } // disable throttle and gps failsafe @@ -197,6 +199,7 @@ void Copter::motor_test_stop() // disarm motors motors->armed(false); + hal.util->set_soft_armed(false); // reset timeout motor_test_start_ms = 0;