Skip to content

Commit

Permalink
AP_Periph: allow for RTCMv3 packets larger than 300 bytes
Browse files Browse the repository at this point in the history
with newer receivers, RTCMv3 packets can be larger than 300
  • Loading branch information
tridge committed Feb 25, 2024
1 parent 297b623 commit 32515fc
Showing 1 changed file with 32 additions and 19 deletions.
51 changes: 32 additions & 19 deletions Tools/AP_Periph/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,27 +249,40 @@ void AP_Periph_FW::send_moving_baseline_msg()
if (len == 0 || data == nullptr) {
return;
}
// send the packet from Moving Base to be used RelPosHeading calc by GPS module
ardupilot_gnss_MovingBaselineData mbldata {};
// get the data from the moving base
static_assert(sizeof(ardupilot_gnss_MovingBaselineData::data.data) == RTCM3_MAX_PACKET_LEN, "Size of Moving Base data is wrong");
mbldata.data.len = len;
memcpy(mbldata.data.data, data, len);
uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {};
const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout());

uint8_t iface_mask = 0;

/*
send the packet from Moving Base to be used RelPosHeading calc by GPS module
for long RTCMv3 packets we may need to split it up
*/

// get the data from the moving base and send as MovingBaselineData message
while (len > 0) {
ardupilot_gnss_MovingBaselineData mbldata {};

const uint16_t n = MIN(len, sizeof(mbldata.data.data));

mbldata.data.len = n;
memcpy(mbldata.data.data, data, n);

uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {};
const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout());

uint8_t iface_mask = 0;
#if HAL_NUM_CAN_IFACES >= 2 && CANARD_MULTI_IFACE
if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) {
iface_mask = 1U<<gps_mb_can_port;
}
if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) {
iface_mask = 1U<<gps_mb_can_port;
}
#endif
canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE,
ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer[0],
total_size,
iface_mask);
canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE,
ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer[0],
total_size,
iface_mask);
len -= n;
data += n;
}

gps.clear_RTCMV3();
#endif // GPS_MOVING_BASELINE
}
Expand Down

0 comments on commit 32515fc

Please sign in to comment.