Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Log DCM wind estimate in DCM message #28339

Merged
merged 4 commits into from
Oct 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 11 additions & 5 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_NavEKF2/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ struct PACKED log_NKF1 {
// @Field: GSX: Gyro Scale Factor (X-axis)
// @Field: GSY: Gyro Scale Factor (Y-axis)
// @Field: GSZ: Gyro Scale Factor (Z-axis)
// @Field: VWN: Estimated wind velocity (North component)
// @Field: VWE: Estimated wind velocity (East component)
// @Field: VWN: Estimated wind velocity (moving-to-North component)
// @Field: VWE: Estimated wind velocity (moving-to-East component)
// @Field: MN: Magnetic field strength (North component)
// @Field: ME: Magnetic field strength (East component)
// @Field: MD: Magnetic field strength (Down component)
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_NavEKF3/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,8 @@ struct PACKED log_XKF1 {
// @Field: AX: Estimated accelerometer X bias
// @Field: AY: Estimated accelerometer Y bias
// @Field: AZ: Estimated accelerometer Z bias
// @Field: VWN: Estimated wind velocity (North component)
// @Field: VWE: Estimated wind velocity (East component)
// @Field: VWN: Estimated wind velocity (moving-to-North component)
// @Field: VWE: Estimated wind velocity (moving-to-East component)
// @Field: MN: Magnetic field strength (North component)
// @Field: ME: Magnetic field strength (East component)
// @Field: MD: Magnetic field strength (Down component)
Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ const AP_Param::GroupInfo SIM::var_info[] = {
// @User: Advanced
AP_GROUPINFO("WIND_SPD", 9, SIM, wind_speed, 0),
// @Param: WIND_DIR
// @DisplayName: Simulated Wind direction
// @DisplayName: Direction simulated wind is coming from
// @Description: Allows you to set wind direction (true deg) in sim
// @Units: deg
// @User: Advanced
Expand Down
Loading