mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Sub: Default INS_GYR_CAL to Never (0)
This commit is contained in:
parent
46771c097a
commit
012f52dc12
@ -812,6 +812,7 @@ void Sub::load_parameters(void)
|
||||
AP_Param::set_default_by_name("ATC_ACCEL_Y_MAX", 110000.0f);
|
||||
AP_Param::set_default_by_name("RC3_TRIM", 1100);
|
||||
AP_Param::set_default_by_name("COMPASS_OFS_MAX", 1000);
|
||||
AP_Param::set_default_by_name("INS_GYR_CAL", 0);
|
||||
}
|
||||
|
||||
void Sub::convert_old_parameters(void)
|
||||
|
Loading…
Reference in New Issue
Block a user