mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3 log position offset as float in meters
This commit is contained in:
parent
0971ef55a4
commit
8173cd442a
|
@ -162,8 +162,8 @@ void NavEKF3_core::Log_Write_XKF4(uint64_t time_us) const
|
|||
sqrtvarM : (int16_t)(100*tempVar),
|
||||
sqrtvarVT : (int16_t)(100*tasVar),
|
||||
tiltErr : sqrtf(MAX(tiltErrorVariance,0.0f)), // estimated 1-sigma tilt error in radians
|
||||
offsetNorth : (int8_t)(offset.x),
|
||||
offsetEast : (int8_t)(offset.y),
|
||||
offsetNorth : offset.x,
|
||||
offsetEast : offset.y,
|
||||
faults : _faultStatus,
|
||||
timeouts : timeoutStatus,
|
||||
solution : solutionStatus.value,
|
||||
|
|
|
@ -182,8 +182,8 @@ struct PACKED log_XKF3 {
|
|||
// @Field: SM: Magnetic field variance
|
||||
// @Field: SVT: Square root of the total airspeed variance
|
||||
// @Field: errRP: Filtered error in roll/pitch estimate
|
||||
// @Field: OFN: Most recent position recent magnitude (North component)
|
||||
// @Field: OFE: Most recent position recent magnitude (East component)
|
||||
// @Field: OFN: Most recent position reset (North component)
|
||||
// @Field: OFE: Most recent position reset (East component)
|
||||
// @Field: FS: Filter fault status
|
||||
// @Field: TS: Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement)
|
||||
// @Field: SS: Filter solution status
|
||||
|
@ -199,8 +199,8 @@ struct PACKED log_XKF4 {
|
|||
int16_t sqrtvarM;
|
||||
int16_t sqrtvarVT;
|
||||
float tiltErr;
|
||||
int8_t offsetNorth;
|
||||
int8_t offsetEast;
|
||||
float offsetNorth;
|
||||
float offsetEast;
|
||||
uint16_t faults;
|
||||
uint8_t timeouts;
|
||||
uint32_t solution;
|
||||
|
@ -428,7 +428,7 @@ struct PACKED log_XKV {
|
|||
{ LOG_XKF3_MSG, sizeof(log_XKF3), \
|
||||
"XKF3","QBcccccchhhccff","TimeUS,C,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT,RErr,ErSc", "s#nnnmmmGGG??--", "F-BBBBBBCCCBB00" }, \
|
||||
{ LOG_XKF4_MSG, sizeof(log_XKF4), \
|
||||
"XKF4","QBcccccfbbHBIHb","TimeUS,C,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s#------??-----", "F-------??-----" }, \
|
||||
"XKF4","QBcccccfffHBIHb","TimeUS,C,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI", "s#------mm-----", "F-------??-----" }, \
|
||||
{ LOG_XKF5_MSG, sizeof(log_XKF5), \
|
||||
"XKF5","QBBhhhcccCCfff","TimeUS,C,NI,FIX,FIY,AFI,HAGL,offset,RI,rng,Herr,eAng,eVel,ePos", "s#----m???mrnm", "F-----BBBBB000" }, \
|
||||
{ LOG_XKFD_MSG, sizeof(log_XKFD), \
|
||||
|
|
Loading…
Reference in New Issue