Browse Source

Copter: Check helicopter parameters during Pre-Arm Checks

mission-4.1.18
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
92de71f993
  1. 9
      ArduCopter/motors.cpp

9
ArduCopter/motors.cpp

@ -536,6 +536,15 @@ bool Copter::pre_arm_checks(bool display_failure) @@ -536,6 +536,15 @@ bool Copter::pre_arm_checks(bool display_failure)
return false;
}
#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

Loading…
Cancel
Save