From c821726bf4e7f6ef2fe7a53648e35cdbdd56c3d7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH] AP_Landing: make AHRS attitude member variables private --- libraries/AP_Landing/AP_Landing_Deepstall.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index d6f24c6eca..0a690acbeb 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -644,7 +644,7 @@ float AP_Landing_Deepstall::update_steering() L1_xtrack_i = constrain_float(L1_xtrack_i, -0.5f, 0.5f); nu1 += L1_xtrack_i; } - desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.yaw) / time_constant; + desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.get_yaw()) / time_constant; } float yaw_rate = landing.ahrs.get_gyro().z;