mirror of https://github.com/ArduPilot/ardupilot
Filter: save freq_min_ratio when saving parameters
This commit is contained in:
parent
a63a32d6f3
commit
1e003871b0
|
@ -338,6 +338,7 @@ void HarmonicNotchFilterParams::save_params()
|
|||
_attenuation_dB.save();
|
||||
_harmonics.save();
|
||||
_reference.save();
|
||||
_freq_min_ratio.save();
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue