diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 0c8bc6b058..031a9a0d26 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -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(); diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index 1e53107c6b..947c6496c9 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -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