mirror of https://github.com/ArduPilot/ardupilot
ACM: allow users to set the AHRS_YAW_P and AHRS_RP_P
the forced set left users with parameters they couldn't use
This commit is contained in:
parent
b01907cf23
commit
c2dc920d02
|
@ -369,6 +369,16 @@ static void load_parameters(void)
|
|||
ahrs.gps_gain.set_and_save(0.0);
|
||||
}
|
||||
|
||||
// setup different AHRS gains for ArduCopter than the default
|
||||
// but allow users to override in their config
|
||||
if (!ahrs._kp.load()) {
|
||||
ahrs._kp.set_and_save(0.1);
|
||||
}
|
||||
if (!ahrs._kp_yaw.load()) {
|
||||
ahrs._kp_yaw.set_and_save(0.1);
|
||||
}
|
||||
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
|
|
|
@ -148,9 +148,6 @@ static void init_arm_motors()
|
|||
startup_ground();
|
||||
}
|
||||
|
||||
ahrs._kp.set(0.1);
|
||||
ahrs._kp_yaw.set(0.1);
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
// read Baro pressure at ground -
|
||||
// this resets Baro for more accuracy
|
||||
|
|
Loading…
Reference in New Issue