Browse Source

Copter: move check_ekf_reset to ekf_check.cpp

No functional change
master
Randy Mackay 8 years ago
parent
commit
35864c6226
  1. 4
      ArduCopter/ArduCopter.cpp
  2. 12
      ArduCopter/Attitude.cpp
  3. 2
      ArduCopter/Copter.h
  4. 14
      ArduCopter/ekf_check.cpp

4
ArduCopter/ArduCopter.cpp

@ -264,8 +264,8 @@ void Copter::fast_loop() @@ -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();

12
ArduCopter/Attitude.cpp

@ -49,18 +49,6 @@ float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle) @@ -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
*************************************************************/

2
ArduCopter/Copter.h

@ -680,7 +680,7 @@ private: @@ -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();

14
ArduCopter/ekf_check.cpp

@ -168,3 +168,17 @@ void Copter::failsafe_ekf_off_event(void) @@ -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);
}
}

Loading…
Cancel
Save