Copter: use modified getLastYawResetAngle function

This commit is contained in:
Jonathan Challinger 2015-09-17 15:01:27 -07:00 committed by Randy Mackay
parent 9f59b6f7b5
commit e47175862a
3 changed files with 7 additions and 2 deletions

View File

@ -53,8 +53,10 @@ float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
void Copter::check_ekf_yaw_reset()
{
float yaw_angle_change_rad = 0.0f;
if (ahrs.getLastYawResetAngle(yaw_angle_change_rad)) {
uint32_t new_ekfYawReset_ms = ahrs.get_NavEKF().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;
}
}

View File

@ -125,7 +125,8 @@ Copter::Copter(void) :
#endif
in_mavlink_delay(false),
gcs_out_of_time(false),
param_loader(var_info)
param_loader(var_info),
ekfYawReset_ms(0)
{
memset(&current_loc, 0, sizeof(current_loc));

View File

@ -208,6 +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;
// GCS selection
AP_SerialManager serial_manager;
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;