AP_GPS: Only inject RTCM data to the selected GPS device defined in GPS_INJECT_TO parameter
This commit is contained in:
parent
12f83ecf75
commit
5261654756
@ -963,7 +963,7 @@ void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t *msg)
|
|||||||
|
|
||||||
if ((packet.flags & 1) == 0) {
|
if ((packet.flags & 1) == 0) {
|
||||||
// it is not fragmented, pass direct
|
// it is not fragmented, pass direct
|
||||||
inject_data_all(packet.data, packet.len);
|
inject_data(packet.data, packet.len);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1013,7 +1013,7 @@ void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t *msg)
|
|||||||
if (rtcm_buffer->fragment_count != 0 &&
|
if (rtcm_buffer->fragment_count != 0 &&
|
||||||
rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
|
rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
|
||||||
// we have them all, inject
|
// we have them all, inject
|
||||||
inject_data_all(rtcm_buffer->buffer, rtcm_buffer->total_length);
|
inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);
|
||||||
memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
|
memset(rtcm_buffer, 0, sizeof(*rtcm_buffer));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user