mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM: make it possible to set AHRS_GPS_GAIN on ArduCopter
this was affected by the AP_Param change, in particular the constructor ordering. To ensure a user can set AHRS_GPS_GAIN to 1.0 if they want to, we need to do a set_and_save() if the value isn't in EEPROM
This commit is contained in:
parent
dc99586981
commit
03714fc695
@ -358,7 +358,10 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
static void load_parameters(void)
|
||||
{
|
||||
// change the default for the AHRS_GPS_GAIN for ArduCopter
|
||||
ahrs.gps_gain.set(0.0);
|
||||
// if it hasn't been set by the user
|
||||
if (!ahrs.gps_gain.load()) {
|
||||
ahrs.gps_gain.set_and_save(0.0);
|
||||
}
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
Loading…
Reference in New Issue
Block a user