mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Plane: Quadplane: remove motor PWM params check
This commit is contained in:
parent
783a8960e1
commit
e585757338
@ -185,10 +185,6 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
||||
ret = false;
|
||||
}
|
||||
if (!plane.quadplane.motors->check_mot_pwm_params()) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check Q_M_PWM_MIN/MAX");
|
||||
ret = false;
|
||||
}
|
||||
|
||||
if (plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)) {
|
||||
if (!plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto) && (plane.control_mode != &plane.mode_guided)) {
|
||||
|
Loading…
Reference in New Issue
Block a user