mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Logger: allow for larger LOG_FILE_BUFSIZE
larger sizes on F7 and H7 allow for much more rapid loggging
This commit is contained in:
parent
71e4d72fe3
commit
a08a1a4247
libraries/AP_Logger
@ -16,7 +16,11 @@ AP_Logger *AP_Logger::_singleton;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifndef HAL_LOGGING_FILE_BUFSIZE
|
||||
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
|
||||
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_1000
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 200
|
||||
#elif HAL_MEM_CLASS >= HAL_MEM_CLASS_500
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 80
|
||||
#elif HAL_MEM_CLASS >= HAL_MEM_CLASS_300
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 50
|
||||
#else
|
||||
#define HAL_LOGGING_FILE_BUFSIZE 16
|
||||
@ -120,6 +124,9 @@ AP_Logger::AP_Logger(const AP_Int32 &log_bitmask)
|
||||
|
||||
void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
|
||||
{
|
||||
// convert from 8 bit to 16 bit LOG_FILE_BUFSIZE
|
||||
_params.file_bufsize.convert_parameter_width(AP_PARAM_INT8);
|
||||
|
||||
if (hal.util->was_watchdog_armed()) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Forcing logging for watchdog reset");
|
||||
_params.log_disarmed.set(1);
|
||||
|
@ -345,7 +345,7 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
struct {
|
||||
AP_Int8 backend_types;
|
||||
AP_Int8 file_bufsize; // in kilobytes
|
||||
AP_Int16 file_bufsize; // in kilobytes
|
||||
AP_Int8 file_disarm_rot;
|
||||
AP_Int8 log_disarmed;
|
||||
AP_Int8 log_replay;
|
||||
|
Loading…
Reference in New Issue
Block a user