From 3189bd7c0dfb685b636e088e3921d570be377583 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 27 Jan 2022 21:04:03 +0000 Subject: [PATCH] Copter: AutoYaw: use get_slew_yaw_max_degs in place of get_slew_yaw_cds --- ArduCopter/autoyaw.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index 98e2dfd2d97db..44f283bdb7879 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -124,9 +124,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di // get turn speed if (!is_positive(turn_rate_ds)) { // default to default slew rate - _fixed_yaw_slewrate_cds = copter.attitude_control->get_slew_yaw_cds(); + _fixed_yaw_slewrate_cds = copter.attitude_control->get_slew_yaw_max_degs() * 100.0; } else { - _fixed_yaw_slewrate_cds = MIN(copter.attitude_control->get_slew_yaw_cds(), turn_rate_ds * 100.0); + _fixed_yaw_slewrate_cds = MIN(copter.attitude_control->get_slew_yaw_max_degs(), turn_rate_ds) * 100.0; } // set yaw mode