Copter: Change Tradheli arming failure message.

"stop rotor spinning" is not a good indication of what the problem really is.  The user needs to understand they must switch off the rotor speed control switch.  I would prefer to say "Rotor Speed Control Engaged" but we are limited in message length.
This commit is contained in:
Robert Lefebvre 2015-05-28 15:33:52 -04:00 committed by Randy Mackay
parent a8c4274db4
commit 112fef4825
1 changed files with 1 additions and 1 deletions

View File

@ -666,7 +666,7 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
// heli specific arming check
if (!motors.allow_arming()){
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: stop Rotor spinning"));
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Rotor Control Engaged"));
}
return false;
}