From d0cc35af3ea83aba3546491d52e28fe6f73c8f99 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 29 Feb 2024 12:41:34 +1100 Subject: [PATCH] AR_PosControl: adjust for logging having moved into AC_AttitudeControl --- libraries/APM_Control/AR_PosControl.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 112c508934..b6f6fe15ac 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec #define AR_POSCON_POS_P 0.2f // default position P gain @@ -385,7 +386,8 @@ void AR_PosControl::write_log() // convert position to required format Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0; - AP::logger().Write_PSCN(pos_target_2d_cm.x, // position target + // reuse logging from AC_PosControl: + AC_PosControl::Write_PSCN(pos_target_2d_cm.x, // position target curr_pos_NED.x * 100.0, // position _vel_desired.x * 100.0, // desired velocity _vel_target.x * 100.0, // target velocity @@ -393,7 +395,7 @@ void AR_PosControl::write_log() _accel_desired.x * 100.0, // desired accel _accel_target.x * 100.0, // target accel curr_accel_NED.x); // accel - AP::logger().Write_PSCE(pos_target_2d_cm.y, // position target + AC_PosControl::Write_PSCE(pos_target_2d_cm.y, // position target curr_pos_NED.y * 100.0, // position _vel_desired.y * 100.0, // desired velocity _vel_target.y * 100.0, // target velocity