From db3852522f175d8b664d8d7c999a308ba4e22132 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 28 May 2015 15:41:28 -0400 Subject: [PATCH] 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". --- ArduCopter/motors.pde | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 287328c819..11d67bcc8e 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -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 if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) { 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")); +#endif } 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 if (channel_throttle->control_in > get_takeoff_trigger_throttle()) { 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")); +#endif } return false; } // in manual modes throttle must be at zero if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) { 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")); +#endif } return false; }