AP_AHRS: DCM: log estimated wind

This commit is contained in:
Peter Barker 2024-10-05 11:06:24 +10:00 committed by Peter Barker
parent 56de7243f5
commit 8487657137
1 changed files with 11 additions and 5 deletions

View File

@ -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