From 3fff2eaf6d58b6963271b231660c95e567fc38e4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 24 Oct 2019 11:32:42 +1100 Subject: [PATCH] Rover: use ahrs singleton to log ATT, POS and AHRS2 --- APMrover2/Log.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 3cfa25aa58..5c1615a3e2 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -10,13 +10,13 @@ void Rover::Log_Write_Attitude() float desired_pitch_cd = degrees(g2.attitude_control.get_desired_pitch()) * 100.0f; const Vector3f targets(0.0f, desired_pitch_cd, 0.0f); - logger.Write_Attitude(ahrs, targets); + logger.Write_Attitude(targets); #if AP_AHRS_NAVEKF_AVAILABLE AP::ahrs_navekf().Log_Write(); - logger.Write_AHRS2(ahrs); + logger.Write_AHRS2(); #endif - logger.Write_POS(ahrs); + logger.Write_POS(); // log steering rate controller logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());