mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fill in have_pos_abs
This commit is contained in:
parent
b622fe143e
commit
e2d91535d0
|
@ -202,6 +202,7 @@ void AP_AHRS_NavEKF::update_EKF2(void)
|
|||
EKF2.getFilterStatus(-1,filt_state);
|
||||
AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
|
||||
AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
|
||||
AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -274,6 +275,7 @@ void AP_AHRS_NavEKF::update_EKF3(void)
|
|||
EKF3.getFilterStatus(-1,filt_state);
|
||||
AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
|
||||
AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
|
||||
AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue