Browse Source

Copter: log EKF yaw reset event

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
b61ae1a4a1
  1. 1
      ArduCopter/Attitude.cpp
  2. 1
      ArduCopter/defines.h

1
ArduCopter/Attitude.cpp

@ -57,6 +57,7 @@ void Copter::check_ekf_yaw_reset() @@ -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);
}
}

1
ArduCopter/defines.h

@ -350,6 +350,7 @@ enum ThrowModeState { @@ -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

Loading…
Cancel
Save