mirror of https://github.com/ArduPilot/ardupilot
copter: flowhold: move to constant dt filter and provide dt in runtime cutoff frequency update
This commit is contained in:
parent
89297737ea
commit
e97569db8c
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue