Copter: Check helicopter parameters during Pre-Arm Checks
This commit is contained in:
parent
992c9c75bb
commit
92de71f993
@ -536,6 +536,15 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
// check helicopter parameters
|
||||||
|
if (!motors.parameter_check()) {
|
||||||
|
if (display_failure) {
|
||||||
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check Heli Parameters"));
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif // HELI_FRAME
|
||||||
}
|
}
|
||||||
|
|
||||||
// check throttle is above failsafe throttle
|
// check throttle is above failsafe throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user