Files
PX4-Autopilot/msg/RtcmCorrections.msg
T
Jacob Dahl 0d1fa8d64c fix(gps): split RTCM corrections and moving-baseline uORB topics
The single gps_inject_data topic served two unrelated purposes:
external fixed-base RTCM corrections (from MAVLink GPS_RTCM_DATA or
UAVCAN RTCMStream) and moving-base-to-rover RTCM 4072. In a
dual-GPS-with-moving-base plus fixed-base setup, the two streams
collided on the same queue and the FMU UAVCAN bridge mirrored
fixed-base RTCM onto the MovingBaselineData CAN message, breaking
rover heading or RTK fix (see PX4/PX4-Autopilot#27088).

Split by role:
- rtcm_corrections    (renamed from gps_inject_data): external RTCM
                       flowing into the vehicle; producers are
                       MAVLink, UAVCAN RTCMStream, and GPS drivers in
                       dump mode.
- rtcm_moving_baseline (new): moving-base GPS output intended for a
                       rover; single producer per vehicle.

GPS driver routes publishRTCMCorrections() based on a new
GPSHelper::isMovingBase() virtual (overridden in UBX). Septentrio's
publish_rtcm_corrections() always publishes to rtcm_moving_baseline
(only the Secondary moving base calls it). Rover-side consumers
(gps, septentrio, uavcan bridge) drain both topics independently;
each gets its own stale-link switchover state.

FMU UAVCAN bridge: two independent drain loops, one per topic. No
more dual-publish of a single uORB message onto both RTCMStream and
MovingBaselineData CAN streams.

CANnode MovingBaselineDataPub subscribes to rtcm_moving_baseline and
drops the bus_type == UAVCAN heuristic that was papering over the
conflation. CANnode RTCMStream subscriber switches to
PublicationMulti so multiple CAN RTCM sources coexist (e.g. dual
rovers outputting MSM7 for logging plus a fixed-base feed).

Signed-off-by: Jacob Dahl <dahl.jakejacob@gmail.com>
2026-04-15 17:26:08 -08:00

12 lines
399 B
Plaintext

uint64 timestamp # time since system start (microseconds)
uint32 device_id # unique device ID of the publisher that produced this RTCM
uint16 len # length of data
uint8 flags # LSB: 1=fragmented
uint8[300] data # RTCM3 correction data (from a fixed base, or another GPS)
uint8 ORB_QUEUE_LENGTH = 8
uint8 MAX_INSTANCES = 4