AP_Periph: raise CAN priorty of MovingBaseline data

and raise CAN buffer size for lots of movingbaseline data
This commit is contained in:
Andrew Tridgell 2023-06-25 16:10:58 +10:00
parent 848e1bfdf8
commit a7d51898da
1 changed files with 5 additions and 1 deletions

View File

@ -59,6 +59,8 @@ extern AP_Periph_FW periph;
#ifndef HAL_CAN_POOL_SIZE #ifndef HAL_CAN_POOL_SIZE
#if HAL_CANFD_SUPPORTED #if HAL_CANFD_SUPPORTED
#define HAL_CAN_POOL_SIZE 16000 #define HAL_CAN_POOL_SIZE 16000
#elif GPS_MOVING_BASELINE
#define HAL_CAN_POOL_SIZE 8000
#else #else
#define HAL_CAN_POOL_SIZE 4000 #define HAL_CAN_POOL_SIZE 4000
#endif #endif
@ -2151,9 +2153,11 @@ void AP_Periph_FW::send_moving_baseline_msg()
} else } else
#endif #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, canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE,
ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID,
CANARD_TRANSFER_PRIORITY_LOW, CANARD_TRANSFER_PRIORITY_MEDIUM,
&buffer[0], &buffer[0],
total_size); total_size);
} }