Copter: fix MAV_CMD_CONDITION_YAW with relative angle when WP_YAW_BEHAVIOR = 0

This commit is contained in:
chobits tai 2024-06-17 09:30:41 +08:00 committed by Randy Mackay
parent a322ba4f77
commit 3b24530cc2
1 changed files with 3 additions and 0 deletions

View File

@ -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