mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: AP_Arming: sanity-check fs timeout parameters
This commit is contained in:
parent
3af5be76aa
commit
1a724ded2a
@ -35,6 +35,13 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
||||
// Check airspeed sensor
|
||||
ret &= AP_Arming::airspeed_checks(report);
|
||||
|
||||
if (plane.g.long_fs_timeout < plane.g.short_fs_timeout) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT");
|
||||
}
|
||||
ret = false;
|
||||
}
|
||||
|
||||
if (plane.aparm.roll_limit_cd < 300) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.aparm.roll_limit_cd);
|
||||
|
Loading…
Reference in New Issue
Block a user