Skip to content

Commit

Permalink
copter: flowhold: move to constant dt filter and provide dt in runtim…
Browse files Browse the repository at this point in the history
…e cutoff frequency update
  • Loading branch information
IamPete1 authored and tridge committed Aug 19, 2024
1 parent 8929773 commit e97569d
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -978,7 +978,7 @@ class ModeFlowHold : public Mode {
// 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();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit e97569d

Please sign in to comment.