mirror of https://github.com/ArduPilot/ardupilot
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;
|
||||
}
|
||||
|
||||
if (!plane.quadplane.motors->initialised_ok()) {
|
||||
check_failed(display_failure, "Quadplane: check motor setup");
|
||||
char failure_msg[50] {};
|
||||
if (!plane.quadplane.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
|
||||
check_failed(display_failure, "Motors: %s", failure_msg);
|
||||
ret = false;
|
||||
}
|
||||
|
||||
|
@ -176,7 +177,6 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
|||
}
|
||||
|
||||
// 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))) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
||||
ret = false;
|
||||
|
|
Loading…
Reference in New Issue