AP_NavEKF3: use selected GPS for gps_yaw_deg()

more than one GPS could provide yaw
This commit is contained in:
Andrew Tridgell 2020-11-07 11:38:25 +11:00
parent f4c3d7286c
commit a0de6c620f
1 changed files with 1 additions and 1 deletions

View File

@ -682,7 +682,7 @@ void NavEKF3_core::readGpsData()
// if the GPS has yaw data then input that as well // if the GPS has yaw data then input that as well
float yaw_deg, yaw_accuracy_deg; float yaw_deg, yaw_accuracy_deg;
if (AP::dal().gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) { if (AP::dal().gps().gps_yaw_deg(selected_gps, yaw_deg, yaw_accuracy_deg)) {
// GPS modules are rather too optimistic about their // GPS modules are rather too optimistic about their
// accuracy. Set to min of 5 degrees here to prevent // accuracy. Set to min of 5 degrees here to prevent
// the user constantly receiving warnings about high // the user constantly receiving warnings about high