mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed RTK injection when first module is a BASE
this is a partial backport of #24132 which fixes RTK injection when the 1st GPS module is a DroneCAN RTK rover. Without this change RTCM injection for RTK fix on the base will only work if it happens to come up as the first module
This commit is contained in:
parent
16d617c62d
commit
544e38cf82
|
@ -947,9 +947,12 @@ void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len)
|
|||
// using a different uavcan instance than the first GPS, as we
|
||||
// send the data as broadcast on all UAVCAN devive ports and we
|
||||
// don't want to send duplicates
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (_detected_module == 0 ||
|
||||
_detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan) {
|
||||
_detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan ||
|
||||
now_ms - _detected_modules[0].last_inject_ms > 2000) {
|
||||
_detected_modules[_detected_module].ap_uavcan->send_RTCMStream(data, len);
|
||||
_detected_modules[_detected_module].last_inject_ms = now_ms;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -124,6 +124,7 @@ private:
|
|||
AP_UAVCAN* ap_uavcan;
|
||||
uint8_t node_id;
|
||||
uint8_t instance;
|
||||
uint32_t last_inject_ms;
|
||||
AP_GPS_UAVCAN* driver;
|
||||
} _detected_modules[GPS_MAX_RECEIVERS];
|
||||
|
||||
|
|
Loading…
Reference in New Issue