AP_GPS: Updates to log message units and help text

Link GPS.Status to AP_GPS::GPS_Status enum
Remove units on fields set to Bytes which are not
Set the unit of GPS.GMS and GRAW.WkMS to ms (no unit specified before).
Change the unit of GPS.HDop and GPA.VDop from m to no-unit.
This commit is contained in:
Simon Hancock 2024-01-17 13:49:49 +00:00 committed by Andrew Tridgell
parent 186b7be086
commit 867f656033
2 changed files with 5 additions and 4 deletions

View File

@ -19,6 +19,7 @@
// @Field: TimeUS: Time since system startup
// @Field: I: GPS instance number
// @Field: Status: GPS Fix type; 2D fix, 3D fix etc.
// @FieldValueEnum: Status: AP_GPS::GPS_Status
// @Field: GMS: milliseconds since start of GPS Week
// @Field: GWk: weeks since 5 Jan 1980
// @Field: NSats: number of satellites visible
@ -204,15 +205,15 @@ struct PACKED log_GPS_RAWS {
#define LOG_STRUCTURE_FROM_GPS \
{ LOG_GPS_MSG, sizeof(log_GPS), \
"GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#---SmDUmnhnh-", "F----0BGGB000--" , true }, \
"GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#-s-S-DUmnhnh-", "F--C-0BGGB000--" , true }, \
{ LOG_GPA_MSG, sizeof(log_GPA), \
"GPA", "QBCCCCfBIHfHH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta,Und,RTCMFU,RTCMFD", "s#mmmnd-ssm--", "F-BBBB0-CC0--" , true }, \
"GPA", "QBCCCCfBIHfHH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta,Und,RTCMFU,RTCMFD", "s#-mmnd-ssm--", "F-BBBB0-CC0--" , true }, \
{ LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \
"UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s#-----", "F------" , true }, \
{ LOG_GPS_UBX2_MSG, sizeof(log_Ubx2), \
"UBX2", "QBbBbB", "TimeUS,Instance,ofsI,magI,ofsQ,magQ", "s#----", "F-----" , true }, \
{ LOG_GPS_RAW_MSG, sizeof(log_GPS_RAW), \
"GRAW", "QIHBBddfBbB", "TimeUS,WkMS,Week,numSV,sv,cpMes,prMes,doMes,mesQI,cno,lli", "s--S-------", "F--0-------" , true }, \
"GRAW", "QIHBBddfBbB", "TimeUS,WkMS,Week,numSV,sv,cpMes,prMes,doMes,mesQI,cno,lli", "ss-S-------", "FC-0-------" , true }, \
{ LOG_GPS_RAWH_MSG, sizeof(log_GPS_RAWH), \
"GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" , true }, \
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \

View File

@ -74,7 +74,7 @@ struct PACKED log_SbpEvent {
{ LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \
"SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \
{ LOG_MSG_SBPRAWH, sizeof(log_SbpRAWH), \
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" , true }, \
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s-------", "F-------" , true }, \
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" , true }, \
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \