From 09cad7c59d25e555652ec1eee7d47c9961ba4971 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 27 Jan 2018 12:45:46 +0900 Subject: [PATCH] Plane: quadplane integrates attitude control inertial_frame_reset --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 179d733697..95b5deedbd 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -764,7 +764,7 @@ void QuadPlane::check_yaw_reset(void) float yaw_angle_change_rad = 0.0f; uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad); if (new_ekfYawReset_ms != ekfYawReset_ms) { - attitude_control->shift_ef_yaw_target(degrees(yaw_angle_change_rad) * 100); + attitude_control->inertial_frame_reset(); ekfYawReset_ms = new_ekfYawReset_ms; gcs().send_text(MAV_SEVERITY_INFO, "EKF yaw reset %.2f", (double)degrees(yaw_angle_change_rad)); }