AP_Periph: enlarge CANARD pool for CANFD messages

This commit is contained in:
bugobliterator 2022-04-04 16:24:31 +05:30 committed by Andrew Tridgell
parent 527f956786
commit cdb14bd75d
1 changed files with 6 additions and 2 deletions

View File

@ -51,8 +51,12 @@ extern const AP_HAL::HAL &hal;
extern AP_Periph_FW periph; extern AP_Periph_FW periph;
#ifndef HAL_CAN_POOL_SIZE #ifndef HAL_CAN_POOL_SIZE
#if HAL_CANFD_SUPPORTED
#define HAL_CAN_POOL_SIZE 16000
#else
#define HAL_CAN_POOL_SIZE 4000 #define HAL_CAN_POOL_SIZE 4000
#endif #endif
#endif
#ifndef HAL_PERIPH_LOOP_DELAY_US #ifndef HAL_PERIPH_LOOP_DELAY_US
// delay between can loop updates. This needs to be longer on F4 // delay between can loop updates. This needs to be longer on F4
@ -1301,7 +1305,7 @@ static void process1HzTasks(uint64_t timestamp_usec)
*/ */
for (auto &ins : instances) { for (auto &ins : instances) {
if (pool_peak_percent(ins) > 70) { if (pool_peak_percent(ins) > 70) {
printf("WARNING: ENLARGE MEMORY POOL on Iface %d\n", ins.index); printf("WARNING: ENLARGE MEMORY POOL on Iface %d Peak Usage: %u%%\n", ins.index, pool_peak_percent(ins));
} }
} }
} }