mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: Quadplane: use new motors pre arm
This commit is contained in:
parent
b59c179079
commit
84922cba9a
@ -147,8 +147,9 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
|||||||
ret = false;
|
ret = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!plane.quadplane.motors->initialised_ok()) {
|
char failure_msg[50] {};
|
||||||
check_failed(display_failure, "Quadplane: check motor setup");
|
if (!plane.quadplane.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
|
||||||
|
check_failed(display_failure, "Motors: %s", failure_msg);
|
||||||
ret = false;
|
ret = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -176,7 +177,6 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// ensure controllers are OK with us arming:
|
// ensure controllers are OK with us arming:
|
||||||
char failure_msg[50] = {};
|
|
||||||
if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
|
if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
||||||
ret = false;
|
ret = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user