Skip to content

Commit

Permalink
Copter: AutoYaw: use get_slew_yaw_max_degs in place of get_slew_yaw_cds
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and rmackay9 committed Jan 31, 2022
1 parent b364649 commit 3189bd7
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 3189bd7

Please sign in to comment.