When GPS_RAW_DATA is enabled (and UBLOX_RXM_RAW_LOGGING is defined, which is by default the case), the AP_GPS_UBLOX driver will attempt, and in my case fail, to decode U-blox RXM-RAWX messages (“Multi-GNSS raw measurements”). The driver will normally write values from the RAWX message to the DataFlash log using AP_Logger. For each UBX-RXM-RAWX message decoded, one RAWH and one or more RAWS messages will appear in the DataFlash log.
The AP_GPS_UBLOX driver performs a length check when receiving a message. It looks at the length field decoded from the U-blox message, and compares that with the size of a union containing all possible U-blox messages. This ensures that it will automatically reject anything bigger than the largest structure in the union. The union also doubles as the receive buffer. This check is needed to prevent an overflow when receiving a U-blox message.
However, in the struct seen below, the field uint8_t numMeas
determines the amount of entries in the svinfo
field. In the document “u-blox F9 HPG L1L5 1.40 - Interface description” there is no mention of a maximum. In the AP_GPS_UBLOX driver, the preprocessor define UBLOX_MAX_RXM_RAWX_SATS
, which is arguably named incorrectly, is set to 32.
When using an U-blox F9P receiver with helical antenna, when outdoors, numMeas
hovered around 60 during tests. This has caused essentially all RAWX messages to be rejected by the message decoder in the AP_GPS_UBLOX driver.
if (_payload_length > sizeof(_buffer)) {
Debug("large payload %u", (unsigned)_payload_length);
// assume any payload bigger then what we know about is noise
_payload_length = 0;
_step = 0;
goto reset;
}
struct PACKED ubx_rxm_rawx {
double rcvTow;
uint16_t week;
int8_t leapS;
uint8_t numMeas;
uint8_t recStat;
uint8_t reserved1[3];
PACKED struct ubx_rxm_rawx_sv {
double prMes;
double cpMes;
float doMes;
uint8_t gnssId;
uint8_t svId;
uint8_t reserved2; //<-- Should be sigId, more about this second bug below
uint8_t freqId;
uint16_t locktime;
uint8_t cno;
uint8_t prStdev;
uint8_t cpStdev;
uint8_t doStdev;
uint8_t trkStat;
uint8_t reserved3;
} svinfo[UBLOX_MAX_RXM_RAWX_SATS]; // <--Currently 32, turns out to to be too low for F9P receiver
};
union PACKED {
ubx_nav_posllh posllh;
//(...) Many other message types here; redacted for your reading comfort
ubx_rxm_rawx rxm_rawx; // <-- The largest struct in the union
} _buffer;
PS: The naming UBLOX_MAX_RXM_RAWX_SATS
implies that this is about individual sattelites, however, as far as I understand it, due to this receiver being marketed as dual-band, it can pick up multiple measurements from a single sattelite.
In my tests I increased UBLOX_MAX_RXM_RAWX_SATS to 256, the maximum possible with the uint8_t numMeas
field. After this change, the messages came through reliably. I have flown with this change and have not had any crashes (neither kinetic nor firmware related!).
With this change, the size of the ubx_rxm_rawx
struct increases by 7168 bytes, from 1040 to 8208. The same goes for the receive buffer (_buffer
), since the ubx_rxm_rawx struct is the largest struct in the union, even with UBLOX_MAX_RXM_RAWX_SATS at 32, which is currently the case.
Sadly, even with this change, attempting to perform PPK produced completely incorrect GNSS solutions. It turns out that there is a second bug. The reserved2
field, which was at some point presumably indeed unused by the U-blox protocol, is nowadays used for the sigId
field. See the aforementioned interface description document. In my testing, I have added the field to the DFLog log structure, and set this field to the value of the reserved2
field, which holds the sigId value.
struct log_GPS_RAWS pkt = {
LOG_PACKET_HEADER_INIT(LOG_GPS_RAWS_MSG),
time_us : now,
prMes : raw.svinfo[i].prMes,
cpMes : raw.svinfo[i].cpMes,
doMes : raw.svinfo[i].doMes,
gnssId : raw.svinfo[i].gnssId,
svId : raw.svinfo[i].svId,
sigId : raw.svinfo[i].reserved2, // <-- Added this line
freqId : raw.svinfo[i].freqId,
locktime : raw.svinfo[i].locktime,
cno : raw.svinfo[i].cno,
prStdev : raw.svinfo[i].prStdev,
cpStdev : raw.svinfo[i].cpStdev,
doStdev : raw.svinfo[i].doStdev,
trkStat : raw.svinfo[i].trkStat
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
In my testing, I noticed that PPK solutions were no longer obviously wrong once this field was present.
For my testing, I wrote a tool which reconstructs the raw U-blow datastream from a DataFlash log file (only the RAWX messages for now). In my testing, I also captured a raw U-blox datastream from an F9P receiver, after letting it be configured by ArduPilot (to ensure exactly identical configuration). Both the artifically reconstructed U-blox raw data, as well as the captured U-blox raw data was fed into RTKLIB version demo5_b34i
, (from a fork made by a user called rtklibexplorer). Probably “vanilla” RTKLIB 2.4.3 would have yielded the same results. In my case I perfomed post-processing in Kinematic mode, with base station data from a VRS (network PPK).
If there is any interest, I can share the tool I wrote to reconstruct the U-blox raw datastream from a DataFlash binary log file.
Shall I proceed and write a PR for these 2 issues?
PS Based on my findings, it appears that not many are using the GPS_RAW_DATA parameter these days to perform PPK. My guess is that people use other or older receivers, or they use network-RTK, perhaps by using an NTRIP feed on the base station and feeding that to ArduPilot over the telemetry link, avoiding the need for these RAWX messages to be collected. However, there is a case to be made for PPK when doing mapping. Intuitively, it makes more sense to me to collect all raw data during flight, and perform all processing afterwards.
Position data produced by ArduPilot collected without RTK or PPK. Me walking in rectangles with vehicle in hand.
Position data reconstructed with only RAWX observations after the 2 bugfixes. U-blox onboard GNSS solutions are completely ignored. This is purely based on psuedorange and other variables for each signal + VRS PPK corrections. GNSS solution calculated by RTKLib.
This is exactly the same as above, but with the RAWX sigId field left at 0, which was the case with stock Ardupilot, which did not include that field in the RAWS DataFlash messages.