mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: DCM: log estimated wind
This commit is contained in:
parent
56de7243f5
commit
8487657137
@ -116,18 +116,24 @@ AP_AHRS_DCM::update()
|
|||||||
// @Field: Yaw: estimated yaw
|
// @Field: Yaw: estimated yaw
|
||||||
// @Field: ErrRP: lowest estimated gyro drift error
|
// @Field: ErrRP: lowest estimated gyro drift error
|
||||||
// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate
|
// @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(
|
AP::logger().WriteStreaming(
|
||||||
"DCM",
|
"DCM",
|
||||||
"TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw",
|
"TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD",
|
||||||
"s" "d" "d" "d" "d" "h",
|
"s" "d" "d" "d" "d" "h" "n" "n" "n",
|
||||||
"F" "0" "0" "0" "0" "0",
|
"F" "0" "0" "0" "0" "0" "0" "0" "0",
|
||||||
"Q" "f" "f" "f" "f" "f",
|
"Q" "f" "f" "f" "f" "f" "f" "f" "f",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
degrees(roll),
|
degrees(roll),
|
||||||
degrees(pitch),
|
degrees(pitch),
|
||||||
wrap_360(degrees(yaw)),
|
wrap_360(degrees(yaw)),
|
||||||
get_error_rp(),
|
get_error_rp(),
|
||||||
get_error_yaw()
|
get_error_yaw(),
|
||||||
|
_wind.x,
|
||||||
|
_wind.y,
|
||||||
|
_wind.z
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
#endif // HAL_LOGGING_ENABLED
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user