mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter: set fast gains while auto trim is being executed
This commit is contained in:
parent
67e02a815f
commit
3b5b2eba6e
@ -161,6 +161,12 @@ static void auto_trim()
|
|||||||
//g.rc_2.dead_zone = 60;
|
//g.rc_2.dead_zone = 60;
|
||||||
|
|
||||||
auto_level_counter--;
|
auto_level_counter--;
|
||||||
|
|
||||||
|
if( motors.armed() ) {
|
||||||
|
// set high AHRS gains to force accelerometers to impact attitude estimate
|
||||||
|
ahrs.set_fast_gains(true);
|
||||||
|
}
|
||||||
|
|
||||||
trim_accel();
|
trim_accel();
|
||||||
led_mode = AUTO_TRIM_LEDS;
|
led_mode = AUTO_TRIM_LEDS;
|
||||||
do_simple = false;
|
do_simple = false;
|
||||||
@ -174,6 +180,11 @@ static void auto_trim()
|
|||||||
|
|
||||||
reset_control_switch();
|
reset_control_switch();
|
||||||
|
|
||||||
|
// go back to normal AHRS gains
|
||||||
|
if( motors.armed() ) {
|
||||||
|
ahrs.set_fast_gains(false);
|
||||||
|
}
|
||||||
|
|
||||||
//Serial.println("Done");
|
//Serial.println("Done");
|
||||||
auto_level_counter = 0;
|
auto_level_counter = 0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user