Copter: Arming failures should say Collective not Throttle for Tradheli.

Referring to Collective Pitch as Throttle is confusing for helicopter users as the throttle is really on the motor and not the "throttle stick".
This commit is contained in:
Robert Lefebvre 2015-05-28 15:41:28 -04:00 committed by Randy Mackay
parent 112fef4825
commit db3852522f
1 changed files with 12 additions and 0 deletions

View File

@ -711,7 +711,11 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
// check throttle is not too low - must be above failsafe throttle // check throttle is not too low - must be above failsafe throttle
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) { if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Collective below Failsafe"));
#else
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle below Failsafe")); gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle below Failsafe"));
#endif
} }
return false; return false;
} }
@ -721,14 +725,22 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
// above top of deadband is too always high // above top of deadband is too always high
if (channel_throttle->control_in > get_takeoff_trigger_throttle()) { if (channel_throttle->control_in > get_takeoff_trigger_throttle()) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Collective too high"));
#else
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle too high")); gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle too high"));
#endif
} }
return false; return false;
} }
// in manual modes throttle must be at zero // in manual modes throttle must be at zero
if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) { if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) {
if (display_failure) { if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Collective too high"));
#else
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle too high")); gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Throttle too high"));
#endif
} }
return false; return false;
} }