diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index 749a830f4d..287cb8e4f9 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -110,6 +110,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