Copter: mode circle: trigger param value change

This commit is contained in:
Iampete1 2021-05-02 01:41:53 +01:00 committed by Andrew Tridgell
parent e995e8873c
commit 0545c3941b
1 changed files with 3 additions and 0 deletions

View File

@ -40,6 +40,9 @@ void ModeCircle::run()
pilot_yaw_override = true;
}
// Check for any change in params and update in real time
copter.circle_nav->check_param_change();
// pilot changes to circle rate and radius
// skip if in radio failsafe
if (!copter.failsafe.radio && copter.circle_nav->pilot_control_enabled()) {