From 8487657137593d8b89f94fe754e74f66d392c01b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 5 Oct 2024 11:06:24 +1000 Subject: [PATCH] AP_AHRS: DCM: log estimated wind --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index f1ee8e29be..eb10db1b45 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -116,18 +116,24 @@ AP_AHRS_DCM::update() // @Field: Yaw: estimated yaw // @Field: ErrRP: lowest estimated gyro drift error // @Field: ErrYaw: difference between measured yaw and DCM yaw estimate +// @Field: VWN: wind velocity, to-the-North component +// @Field: VWE: wind velocity, to-the-East component +// @Field: VWD: wind velocity, Up-to-Down component AP::logger().WriteStreaming( "DCM", - "TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw", - "s" "d" "d" "d" "d" "h", - "F" "0" "0" "0" "0" "0", - "Q" "f" "f" "f" "f" "f", + "TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD", + "s" "d" "d" "d" "d" "h" "n" "n" "n", + "F" "0" "0" "0" "0" "0" "0" "0" "0", + "Q" "f" "f" "f" "f" "f" "f" "f" "f", AP_HAL::micros64(), degrees(roll), degrees(pitch), wrap_360(degrees(yaw)), get_error_rp(), - get_error_yaw() + get_error_yaw(), + _wind.x, + _wind.y, + _wind.z ); } #endif // HAL_LOGGING_ENABLED