diff --git a/APMrover2/Parameters.pde b/APMrover2/Parameters.pde index fc0674d19f..6de0f91409 100644 --- a/APMrover2/Parameters.pde +++ b/APMrover2/Parameters.pde @@ -569,10 +569,6 @@ 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(8); }