mirror of https://github.com/ArduPilot/ardupilot
Rover: moved override of defaults to load_parameters()
This commit is contained in:
parent
fc1228eb48
commit
983ca71796
|
@ -511,4 +511,11 @@ static void load_parameters(void)
|
|||
|
||||
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||
}
|
||||
|
||||
// set a lower default filter frequency for rovers, due to very
|
||||
// high vibration levels on rough surfaces
|
||||
ins.set_default_filter(5);
|
||||
|
||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||
L1_controller.set_default_period(6);
|
||||
}
|
||||
|
|
|
@ -395,10 +395,6 @@ static void startup_INS_ground(bool force_accel_level)
|
|||
ins_sample_rate,
|
||||
flash_leds);
|
||||
|
||||
// set a lower default filter frequency for rovers, due to very
|
||||
// high vibration levels on rough surfaces
|
||||
ins.set_default_filter(5);
|
||||
|
||||
if (force_accel_level) {
|
||||
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
|
||||
// levelling on each boot, and instead rely on the user to do
|
||||
|
|
Loading…
Reference in New Issue