mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
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:
parent
31ea32dc9c
commit
6056d4fb7b
@ -1604,16 +1604,12 @@ void update_roll_pitch_mode(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
if(g.rc_3.control_in == 0 && control_mode <= ACRO) {
|
if(g.rc_3.control_in == 0 && control_mode <= ACRO) {
|
||||||
reset_rate_I();
|
reset_rate_I();
|
||||||
reset_stability_I();
|
reset_stability_I();
|
||||||
}
|
}
|
||||||
|
#endif //HELI_FRAME
|
||||||
//if(takeoff_complete == false){
|
|
||||||
// reset these I terms to prevent awkward tipping on takeoff
|
|
||||||
//reset_rate_I();
|
|
||||||
//reset_stability_I();
|
|
||||||
//}
|
|
||||||
|
|
||||||
if(ap_system.new_radio_frame) {
|
if(ap_system.new_radio_frame) {
|
||||||
// clear new radio frame info
|
// clear new radio frame info
|
||||||
|
Loading…
Reference in New Issue
Block a user