From 96a70df75be93ec52d41307b36d7e16c4680d9a3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 10 Nov 2024 14:34:41 +0000 Subject: [PATCH] Copter: address review comments --- ArduCopter/Copter.h | 2 +- ArduCopter/rate_thread.cpp | 5 +---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 491a2eb34c..a94edddef2 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -753,7 +753,7 @@ private: void rate_controller_thread(); void rate_controller_filter_update(); void rate_controller_log_update(); - uint8_t rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high); + void rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high); void enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates); void disable_fast_rate_loop(RateControllerRates& rates); void update_dynamic_notch_at_specified_rate_main(); diff --git a/ArduCopter/rate_thread.cpp b/ArduCopter/rate_thread.cpp index ac533165e3..5b64301fb7 100644 --- a/ArduCopter/rate_thread.cpp +++ b/ArduCopter/rate_thread.cpp @@ -248,7 +248,6 @@ void Copter::rate_controller_thread() const float dt = dt_us * 1.0e-6; last_run_us = now_us; - motors->set_dt(sensor_dt); // check if we are falling behind if (ins.get_num_gyro_samples() > 2) { running_slow++; @@ -420,7 +419,7 @@ void Copter::rate_controller_filter_update() /* update rate controller rates and return the logging rate */ -uint8_t Copter::rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high) +void Copter::rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high) { const uint32_t attitude_rate = ins.get_raw_gyro_rate_hz() / rate_decimation; attitude_control->set_notch_sample_rate(attitude_rate); @@ -439,8 +438,6 @@ uint8_t Copter::rate_controller_set_rates(uint8_t rate_decimation, RateControlle #endif rates.main_loop_rate = calc_gyro_decimation(rate_decimation, AP::scheduler().get_filtered_loop_rate_hz()); rates.filter_rate = calc_gyro_decimation(rate_decimation, ins.get_raw_gyro_rate_hz() / 2); - - return 0; } // enable the fast rate thread using the provided decimation rate and record the new output rates