From cdd4570f02f70af0ba8c0d22d9767a2e44c3be6d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 24 Sep 2015 15:57:22 +0900 Subject: [PATCH] Copter: fix init order of ekfYawReset_ms --- ArduCopter/Copter.cpp | 3 +-- ArduCopter/Copter.h | 3 ++- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 6047243ee4..0ef6474da0 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -125,8 +125,7 @@ Copter::Copter(void) : #endif in_mavlink_delay(false), gcs_out_of_time(false), - param_loader(var_info), - ekfYawReset_ms(0) + param_loader(var_info) { memset(¤t_loc, 0, sizeof(current_loc)); diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 9b0debafb5..0b306bd8fc 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -208,7 +208,8 @@ private: // scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise float ekfNavVelGainScaler; - uint32_t ekfYawReset_ms; + // system time in milliseconds of last recorded yaw reset from ekf + uint32_t ekfYawReset_ms = 0; // GCS selection AP_SerialManager serial_manager;