mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
DataFlash: allow HAL to specify dataflash buffer sizes
This commit is contained in:
parent
dc15cbd513
commit
932cc4bb69
@ -15,6 +15,14 @@ DataFlash_Class *DataFlash_Class::_instance;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifndef HAL_DATAFLASH_FILE_BUFSIZE
|
||||
#define HAL_DATAFLASH_FILE_BUFSIZE 16
|
||||
#endif
|
||||
|
||||
#ifndef HAL_DATAFLASH_MAV_BUFSIZE
|
||||
#define HAL_DATAFLASH_MAV_BUFSIZE 8
|
||||
#endif
|
||||
|
||||
const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
|
||||
// @Param: _BACKEND_TYPE
|
||||
// @DisplayName: DataFlash Backend Storage type
|
||||
@ -27,7 +35,7 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
|
||||
// @DisplayName: Maximum DataFlash File Backend buffer size (in kilobytes)
|
||||
// @Description: The DataFlash_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, 16),
|
||||
AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, HAL_DATAFLASH_FILE_BUFSIZE),
|
||||
|
||||
// @Param: _DISARMED
|
||||
// @DisplayName: Enable logging while disarmed
|
||||
@ -55,7 +63,7 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
|
||||
// @Description: Maximum amount of memory to allocate to DataFlash-over-mavlink
|
||||
// @User: Advanced
|
||||
// @Units: kB
|
||||
AP_GROUPINFO("_MAV_BUFSIZE", 5, DataFlash_Class, _params.mav_bufsize, 8),
|
||||
AP_GROUPINFO("_MAV_BUFSIZE", 5, DataFlash_Class, _params.mav_bufsize, HAL_DATAFLASH_MAV_BUFSIZE),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user