mirror of https://github.com/ArduPilot/ardupilot
Plane: check SCHED_LOOP_RATE for quadplane
This commit is contained in:
parent
898c2faaab
commit
e2abaefc44
|
@ -61,6 +61,13 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
||||||
ret = false;
|
ret = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (plane.quadplane.available() && plane.scheduler.get_loop_rate_hz() < 100) {
|
||||||
|
if (report) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: quadplane needs SCHED_LOOP_RATE > 100");
|
||||||
|
}
|
||||||
|
ret = false;
|
||||||
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue