APM_Control: logging_started needs to be static

prevents writing log headers twice
This commit is contained in:
Andrew Tridgell 2014-04-21 07:13:06 +10:00
parent 623cbc3316
commit 7f9a9107c7
2 changed files with 3 additions and 1 deletions

View File

@ -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,

View File

@ -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;