copter: flowhold: move to constant dt filter and provide dt in runtime cutoff frequency update

This commit is contained in:
Iampete1 2024-07-27 13:14:08 +01:00 committed by Andrew Tridgell
parent 89297737ea
commit e97569db8c
2 changed files with 2 additions and 2 deletions

View File

@ -978,7 +978,7 @@ private:
// calculate attitude from flow data
void flow_to_angle(Vector2f &bf_angle);
LowPassFilterVector2f flow_filter;
LowPassFilterConstDtVector2f flow_filter;
bool flowhold_init(bool ignore_checks);
void flowhold_run();

View File

@ -240,7 +240,7 @@ void ModeFlowHold::run()
// check for filter change
if (!is_equal(flow_filter.get_cutoff_freq(), flow_filter_hz.get())) {
flow_filter.set_cutoff_frequency(flow_filter_hz.get());
flow_filter.set_cutoff_frequency(copter.scheduler.get_loop_rate_hz(), flow_filter_hz.get());
}
// get pilot desired climb rate