Skip to content

Commit

Permalink
Copter: fix MAV_CMD_CONDITION_YAW with relative angle when WP_YAW_BEH…
Browse files Browse the repository at this point in the history
…AVIOR = 0
  • Loading branch information
chobitsfan authored and rmackay9 committed Jun 18, 2024
1 parent a322ba4 commit 3b24530
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di

// calculate final angle as relative to vehicle heading or absolute
if (relative_angle) {
if (_mode == Mode::HOLD) {
_yaw_angle_cd = copter.ahrs.yaw_sensor;
}
_fixed_yaw_offset_cd = angle_deg * 100.0 * (direction >= 0 ? 1.0 : -1.0);
} else {
// absolute angle
Expand Down

0 comments on commit 3b24530

Please sign in to comment.