mirror of https://github.com/ArduPilot/ardupilot
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
f33d15ab80
commit
72935345ea
|
@ -358,7 +358,10 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||||
static void load_parameters(void)
|
static void load_parameters(void)
|
||||||
{
|
{
|
||||||
// change the default for the AHRS_GPS_GAIN for ArduCopter
|
// 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() ||
|
if (!g.format_version.load() ||
|
||||||
g.format_version != Parameters::k_format_version) {
|
g.format_version != Parameters::k_format_version) {
|
||||||
|
|
Loading…
Reference in New Issue