mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: disable centrifugal force correction when disarmed
This commit is contained in:
parent
30faf87715
commit
372ebb602c
@ -966,6 +966,8 @@ static void load_parameters(void)
|
|||||||
if (!ahrs.gps_gain.load()) {
|
if (!ahrs.gps_gain.load()) {
|
||||||
ahrs.gps_gain.set_and_save(1.0);
|
ahrs.gps_gain.set_and_save(1.0);
|
||||||
}
|
}
|
||||||
|
// set gps_gain to zero, it will be set back to 1 as part of the arming process
|
||||||
|
ahrs.gps_gain.set(0);
|
||||||
|
|
||||||
// setup different AHRS gains for ArduCopter than the default
|
// setup different AHRS gains for ArduCopter than the default
|
||||||
// but allow users to override in their config
|
// but allow users to override in their config
|
||||||
|
@ -144,6 +144,9 @@ static void init_arm_motors()
|
|||||||
ahrs2.set_fast_gains(false);
|
ahrs2.set_fast_gains(false);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// enable gps velocity based centrefugal force compensation
|
||||||
|
ahrs.gps_gain.load();
|
||||||
|
|
||||||
// finally actually arm the motors
|
// finally actually arm the motors
|
||||||
motors.armed(true);
|
motors.armed(true);
|
||||||
|
|
||||||
@ -209,6 +212,9 @@ static void init_disarm_motors()
|
|||||||
#if SECONDARY_DMP_ENABLED == ENABLED
|
#if SECONDARY_DMP_ENABLED == ENABLED
|
||||||
ahrs2.set_fast_gains(true);
|
ahrs2.set_fast_gains(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// disable gps velocity based centrefugal force compensation
|
||||||
|
ahrs.gps_gain.set(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*****************************************
|
/*****************************************
|
||||||
|
Loading…
Reference in New Issue
Block a user