mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
DataFlash: Moving parameter logging to be after all systems have started
Moved Log_Write_Parameters to be public so we can call it from the vehcile code at the end of the startup sequence. We needed to do this because parameters like COMPASS_EXTERNAL are modified by the startup code and if we log the parameters too early we will be recording the wrong value.
This commit is contained in:
parent
2c3cff7f84
commit
7d1bf75aa8
@ -87,6 +87,7 @@ public:
|
||||
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
|
||||
void Log_Write_Compass(const Compass &compass);
|
||||
void Log_Write_Mode(uint8_t mode);
|
||||
void Log_Write_Parameters(void);
|
||||
|
||||
// This structure provides information on the internal member data of a PID for logging purposes
|
||||
struct PID_Info {
|
||||
@ -120,7 +121,6 @@ protected:
|
||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||
void Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
||||
enum ap_var_type type);
|
||||
void Log_Write_Parameters(void);
|
||||
virtual uint16_t start_new_log(void) = 0;
|
||||
|
||||
const struct LogStructure *_structures;
|
||||
|
@ -591,8 +591,6 @@ uint16_t DataFlash_Class::StartNewLog(void)
|
||||
hal.scheduler->delay(10);
|
||||
}
|
||||
|
||||
// and all current parameters
|
||||
Log_Write_Parameters();
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user