From e2de9d62cdedd90857bb7c68d9661d0a47b5d9e5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 10 Mar 2018 21:00:57 +1100 Subject: [PATCH] APM_Control: use ins singleton --- libraries/APM_Control/AP_YawController.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 6ee363329d..9eef35417d 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -108,7 +108,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator) float omega_z = _ahrs.get_gyro().z; // Get the accln vector (m/s^2) - float accel_y = _ahrs.get_ins().get_accel().y; + float accel_y = AP::ins().get_accel().y; // Subtract the steady turn component of rate from the measured rate // to calculate the rate relative to the turn requirement in degrees/sec