From 7f9a9107c71f43b5e6521d7dd86fc7b28c355183 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Apr 2014 07:13:06 +1000 Subject: [PATCH] APM_Control: logging_started needs to be static prevents writing log headers twice --- libraries/APM_Control/AP_AutoTune.cpp | 2 ++ libraries/APM_Control/AP_AutoTune.h | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 67224791b4..688db3ad39 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -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, diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 94eaad6d5c..700f92db40 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -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;