From 6056d4fb7b23cf81c078de5caf2e5c7e999b678e Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Mon, 26 Nov 2012 18:49:24 -0500 Subject: [PATCH] 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. --- ArduCopter/ArduCopter.pde | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 98cb0aba88..f762599d6b 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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