mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: pass format string through to check_failed
This commit is contained in:
parent
95b8c12454
commit
6f4167b85b
@ -255,7 +255,7 @@ bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure)
|
||||
#else
|
||||
const char *failmsg = "Throttle below Failsafe";
|
||||
#endif
|
||||
check_failed(ARMING_CHECK_RC, display_failure, failmsg);
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s", failmsg);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user