mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: remove incorrect units from yaw esimtator LoggerMessage
This commit is contained in:
parent
7dfc285f2a
commit
aa3165b71c
|
@ -363,11 +363,11 @@ void NavEKF3::Log_Write_GSF(uint8_t _core, uint64_t time_us) const
|
|||
// @Field: Y2: Yaw estimate from individual EKF filter 2 (rad)
|
||||
// @Field: Y3: Yaw estimate from individual EKF filter 3 (rad)
|
||||
// @Field: Y4: Yaw estimate from individual EKF filter 4 (rad)
|
||||
// @Field: W0: Weighting applied to yaw estimate from individual EKF filter 0 (rad)
|
||||
// @Field: W1: Weighting applied to yaw estimate from individual EKF filter 1 (rad)
|
||||
// @Field: W2: Weighting applied to yaw estimate from individual EKF filter 2 (rad)
|
||||
// @Field: W3: Weighting applied to yaw estimate from individual EKF filter 3 (rad)
|
||||
// @Field: W4: Weighting applied to yaw estimate from individual EKF filter 4 (rad)
|
||||
// @Field: W0: Weighting applied to yaw estimate from individual EKF filter 0
|
||||
// @Field: W1: Weighting applied to yaw estimate from individual EKF filter 1
|
||||
// @Field: W2: Weighting applied to yaw estimate from individual EKF filter 2
|
||||
// @Field: W3: Weighting applied to yaw estimate from individual EKF filter 3
|
||||
// @Field: W4: Weighting applied to yaw estimate from individual EKF filter 4
|
||||
|
||||
AP::logger().Write("XKY0",
|
||||
"TimeUS,C,YC,YCS,Y0,Y1,Y2,Y3,Y4,W0,W1,W2,W3,W4",
|
||||
|
|
Loading…
Reference in New Issue