TradHeli: Fixing bug that causes Alt_Hold mode to use the Stab_Throttle scaling. It should not have this scaling, it should have access to full swashplate range.

This commit is contained in:
Robert Lefebvre 2013-01-03 15:19:38 -05:00
parent 6f0868a9f8
commit cbbba3a359

View File

@ -1845,7 +1845,7 @@ void update_throttle_mode(void)
}
#if FRAME_CONFIG == HELI_FRAME
if (roll_pitch_mode == ROLL_PITCH_STABLE){
if (control_mode == STABILIZE){
motors.stab_throttle = true;
} else {
motors.stab_throttle = false;