From 35864c6226313b8bf594f6d0d97fd7e7826dc66b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 10 Oct 2016 15:35:08 +0900 Subject: [PATCH] Copter: move check_ekf_reset to ekf_check.cpp No functional change --- ArduCopter/ArduCopter.cpp | 4 ++-- ArduCopter/Attitude.cpp | 12 ------------ ArduCopter/Copter.h | 2 +- ArduCopter/ekf_check.cpp | 14 ++++++++++++++ 4 files changed, 17 insertions(+), 15 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index f210f1b9b2..32302b4260 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -264,8 +264,8 @@ void Copter::fast_loop() // -------------------- read_inertia(); - // check if ekf has reset target heading - check_ekf_yaw_reset(); + // check if ekf has reset target heading or position + check_ekf_reset(); // run the attitude controllers update_flight_mode(); diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index bdcc379621..0f76a86fad 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -49,18 +49,6 @@ float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle) return stick_angle * g.acro_yaw_p; } -// check for ekf yaw reset and adjust target heading -void Copter::check_ekf_yaw_reset() -{ - float yaw_angle_change_rad = 0.0f; - uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad); - 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); - } -} - /************************************************************* * yaw controllers *************************************************************/ diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3d598fffb0..e59f1ac3b6 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -680,7 +680,7 @@ private: float get_smoothing_gain(); void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max); float get_pilot_desired_yaw_rate(int16_t stick_angle); - void check_ekf_yaw_reset(); + void check_ekf_reset(); float get_roi_yaw(); float get_look_ahead_yaw(); void update_throttle_hover(); diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index f45e3abb31..8cfa09f320 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -168,3 +168,17 @@ void Copter::failsafe_ekf_off_event(void) failsafe.ekf = false; Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_EKFINAV, ERROR_CODE_FAILSAFE_RESOLVED); } + +// check for ekf yaw reset and adjust target heading, also log position reset +void Copter::check_ekf_reset() +{ + // check for yaw reset + float yaw_angle_change_rad = 0.0f; + uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad); + 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); + } + +}