mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_HAL_ChibiOS: fix name for RX Queue size define
This commit is contained in:
parent
4bd0e2f394
commit
5eb0e0a718
@ -45,7 +45,7 @@
|
||||
|
||||
#if HAL_NUM_CAN_IFACES
|
||||
|
||||
#ifndef HAL_CAN_RX_STORAGE_SIZE
|
||||
#ifndef HAL_CAN_RX_QUEUE_SIZE
|
||||
#define HAL_CAN_RX_QUEUE_SIZE 128
|
||||
#endif
|
||||
|
||||
|
@ -48,7 +48,7 @@
|
||||
#include "bxcan.hpp"
|
||||
#include "EventSource.h"
|
||||
|
||||
#ifndef HAL_CAN_RX_STORAGE_SIZE
|
||||
#ifndef HAL_CAN_RX_QUEUE_SIZE
|
||||
#define HAL_CAN_RX_QUEUE_SIZE 128
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user