Rover: set a default filter frequency of 5Hz
this should help rovers on rough surfaces
This commit is contained in:
parent
7b3a674d66
commit
fc1228eb48
@ -394,6 +394,11 @@ static void startup_INS_ground(bool force_accel_level)
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
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
Block a user