From b61ae1a4a196bbd5238c1c53e7ff9cc6b5e5beab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 24 Jun 2016 18:12:30 +0900 Subject: [PATCH] Copter: log EKF yaw reset event --- ArduCopter/Attitude.cpp | 1 + ArduCopter/defines.h | 1 + 2 files changed, 2 insertions(+) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index a22db991fc..294fddcd3e 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -57,6 +57,7 @@ void Copter::check_ekf_yaw_reset() if (new_ekfYawReset_ms != ekfYawReset_ms) { attitude_control.shift_ef_yaw_target(ToDeg(yaw_angle_change_rad) * 100.0f); ekfYawReset_ms = new_ekfYawReset_ms; + Log_Write_Event(DATA_EKF_YAW_RESET); } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 93819abcbb..f5e201ace8 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -350,6 +350,7 @@ enum ThrowModeState { #define DATA_ROTOR_SPEED_BELOW_CRITICAL 59 // Heli only #define DATA_EKF_ALT_RESET 60 #define DATA_LAND_CANCELLED_BY_PILOT 61 +#define DATA_EKF_YAW_RESET 62 // Centi-degrees to radians #define DEGX100 5729.57795f