mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
APM_Control: logging_started needs to be static
prevents writing log headers twice
This commit is contained in:
parent
623cbc3316
commit
7f9a9107c7
@ -66,6 +66,8 @@ extern const AP_HAL::HAL& hal;
|
||||
#define AUTOTUNE_MIN_IMAX 2000
|
||||
#define AUTOTUNE_MAX_IMAX 4000
|
||||
|
||||
bool AP_AutoTune::logging_started = false;
|
||||
|
||||
// constructor
|
||||
AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
|
||||
const AP_Vehicle::FixedWing &parms,
|
||||
|
@ -55,7 +55,7 @@ private:
|
||||
bool saturated_surfaces:1;
|
||||
|
||||
// have we sent log headers
|
||||
bool logging_started:1;
|
||||
static bool logging_started;
|
||||
|
||||
// values to restore if we leave autotune mode
|
||||
ATGains restore;
|
||||
|
Loading…
Reference in New Issue
Block a user