mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_Logger: use HAL_MEM_CLASS for logging buffer size
This commit is contained in:
parent
609a2d95f8
commit
6cd6b37826
@ -15,8 +15,12 @@ AP_Logger *AP_Logger::_singleton;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifndef HAL_LOGGING_FILE_BUFSIZE
|
||||
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 50
|
||||
#else
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 16
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef HAL_LOGGING_MAV_BUFSIZE
|
||||
#define HAL_LOGGING_MAV_BUFSIZE 8
|
||||
|
Loading…
Reference in New Issue
Block a user