ACM: TradHeli

Remove Rate I-term reset when throttle stick is on the bottom.  This could be very bad for helis since it's plausible to use full downstick while flying.
There is obviously a risk here of building up a false I-term on the ground but this isn't a good solution for that anyway.
Also removed what appears to be some deadwood.
This commit is contained in:
Robert Lefebvre 2012-11-26 18:49:24 -05:00
parent 637c9a1a72
commit 8056b78c55

View File

@ -1603,17 +1603,13 @@ void update_roll_pitch_mode(void)
roll_pitch_toy();
break;
}
#if FRAME_CONFIG != HELI_FRAME
if(g.rc_3.control_in == 0 && control_mode <= ACRO) {
reset_rate_I();
reset_stability_I();
}
//if(takeoff_complete == false){
// reset these I terms to prevent awkward tipping on takeoff
//reset_rate_I();
//reset_stability_I();
//}
#endif //HELI_FRAME
if(ap_system.new_radio_frame) {
// clear new radio frame info