diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 4dfb50aaae0d2..7a38f7e9aa42f 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1646,7 +1646,7 @@ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm const uint32_t crc = crc_crc32(0, buf, len); #if HAL_LOGGING_ENABLED - AP::logger().WriteStreaming("RTCM", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI", + AP::logger().WriteStreaming("RTKR", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI", AP_HAL::micros64(), uint8_t(chan), rtcm.parsers[chan]->get_id(), @@ -1670,6 +1670,14 @@ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm rtcm.sent_idx = (rtcm.sent_idx+1) % ARRAY_SIZE(rtcm.sent_crc); if (buf != nullptr && len > 0) { +#if HAL_LOGGING_ENABLED + AP::logger().WriteStreaming("RTKT", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI", + AP_HAL::micros64(), + uint8_t(chan), + rtcm.parsers[chan]->get_id(), + len, + crc); +#endif inject_data(buf, len); } rtcm.parsers[chan]->reset();