Copter: set force log disarmed moved to AP_Arming

This commit is contained in:
Iampete1 2021-08-30 20:26:30 +01:00 committed by Andrew Tridgell
parent 380d962648
commit 38cdc00137

View File

@ -83,8 +83,6 @@ void Copter::crash_check()
// check if crashing for 2 seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
// keep logging even if disarmed:
AP::logger().set_force_log_disarmed(true);
// send message to gcs
gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming: AngErr=%.0f>%.0f, Accel=%.1f<%.1f", angle_error, CRASH_CHECK_ANGLE_DEVIATION_DEG, filtered_acc, CRASH_CHECK_ACCEL_MAX);
// disarm motors