From a7d51898daa719e989d2d94c7b52647efe0a1028 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 25 Jun 2023 16:10:58 +1000 Subject: [PATCH] AP_Periph: raise CAN priorty of MovingBaseline data and raise CAN buffer size for lots of movingbaseline data --- Tools/AP_Periph/can.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 2c7fb6e8d3..8209212d21 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -59,6 +59,8 @@ extern AP_Periph_FW periph; #ifndef HAL_CAN_POOL_SIZE #if HAL_CANFD_SUPPORTED #define HAL_CAN_POOL_SIZE 16000 +#elif GPS_MOVING_BASELINE + #define HAL_CAN_POOL_SIZE 8000 #else #define HAL_CAN_POOL_SIZE 4000 #endif @@ -2151,9 +2153,11 @@ void AP_Periph_FW::send_moving_baseline_msg() } else #endif { + // we use MEDIUM priority on this data as we need to get all + // the data through for RTK moving baseline yaw to work canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, - CANARD_TRANSFER_PRIORITY_LOW, + CANARD_TRANSFER_PRIORITY_MEDIUM, &buffer[0], total_size); }