Skip to content

Commit

Permalink
Copter: switch off fast rate while doing temperature calibration
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Jan 3, 2025
1 parent aee979c commit e0b61d2
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion ArduCopter/rate_thread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,11 @@ void Copter::rate_controller_thread()
#endif

// allow changing option at runtime
if (get_fast_rate_type() == FastRateType::FAST_RATE_DISABLED || ap.motor_test) {
if (get_fast_rate_type() == FastRateType::FAST_RATE_DISABLED || ap.motor_test
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|| ins.temperature_cal_running()
#endif
) {
if (was_using_rate_thread) {
disable_fast_rate_loop(rates);
was_using_rate_thread = false;
Expand Down

0 comments on commit e0b61d2

Please sign in to comment.