|
|
|
@ -185,7 +185,13 @@ public:
@@ -185,7 +185,13 @@ public:
|
|
|
|
|
uint32_t num_dropped(void) const; |
|
|
|
|
|
|
|
|
|
// accesss to public parameters
|
|
|
|
|
bool log_while_disarmed(void) const { return _params.log_disarmed != 0; } |
|
|
|
|
void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; } |
|
|
|
|
bool log_while_disarmed(void) const { |
|
|
|
|
if (_force_log_disarmed) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
return _params.log_disarmed != 0; |
|
|
|
|
} |
|
|
|
|
uint8_t log_replay(void) const { return _params.log_replay; } |
|
|
|
|
|
|
|
|
|
vehicle_startup_message_Log_Writer _vehicle_messages; |
|
|
|
@ -304,7 +310,6 @@ private:
@@ -304,7 +310,6 @@ private:
|
|
|
|
|
|
|
|
|
|
void backend_starting_new_log(const DataFlash_Backend *backend); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
static DataFlash_Class *_instance; |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
@ -329,6 +334,7 @@ private:
@@ -329,6 +334,7 @@ private:
|
|
|
|
|
void Prep(); |
|
|
|
|
|
|
|
|
|
bool _writes_enabled:1; |
|
|
|
|
bool _force_log_disarmed:1; |
|
|
|
|
|
|
|
|
|
/* support for retrieving logs via mavlink: */ |
|
|
|
|
|
|
|
|
|