Skip to content

Commit fe11e77

Browse files
UAVcihangpeterbarker
authored andcommitted
AP_GPS: Fix DNU constant values in AP_GPS_SBF.cpp
bug
1 parent c2045d7 commit fe11e77

1 file changed

Lines changed: 2 additions & 10 deletions

File tree

libraries/AP_GPS/AP_GPS_SBF.cpp

Lines changed: 2 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -590,15 +590,11 @@ AP_GPS_SBF::process_message(void)
590590

591591
check_new_itow(temp.TOW, sbf_msg.length);
592592

593-
constexpr double floatDNU = -2e-10f;
594593
constexpr uint8_t errorBits = 0x8F; // Bits 0-1 are aux 1 baseline
595594
// Bits 2-3 are aux 2 baseline
596595
// Bit 7 is attitude not requested
597-
#pragma GCC diagnostic push
598-
#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
599596
if (((temp.Error & errorBits) == 0)
600-
&& (temp.Cov_HeadHead != floatDNU)) {
601-
#pragma GCC diagnostic pop
597+
&& !is_DNU(temp.Cov_HeadHead)) {
602598
state.gps_yaw_accuracy = sqrtf(temp.Cov_HeadHead);
603599
state.have_gps_yaw_accuracy = true;
604600
} else {
@@ -628,12 +624,9 @@ AP_GPS_SBF::process_message(void)
628624
}
629625
case BaseVectorGeod:
630626
{
631-
#pragma GCC diagnostic push
632-
#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
633627
const msg4028 &temp = sbf_msg.data.msg4028u;
634628

635629
// just breakout any consts we need for Do Not Use (DNU) reasons
636-
constexpr double doubleDNU = -2e-10;
637630
constexpr uint16_t uint16DNU = 65535;
638631

639632
check_new_itow(temp.TOW, sbf_msg.length);
@@ -652,7 +645,7 @@ AP_GPS_SBF::process_message(void)
652645
state.rtk_age_ms = (temp.info.CorrAge != 65535) ? ((uint32_t)temp.info.CorrAge) * 10 : 0;
653646

654647
// copy the position as long as the data isn't DNU, we require NED, and heading before accepting any of it
655-
if ((temp.info.DeltaEast != doubleDNU) && (temp.info.DeltaNorth != doubleDNU) && (temp.info.DeltaUp != doubleDNU) &&
648+
if (!is_DNU(temp.info.DeltaEast) && !is_DNU(temp.info.DeltaNorth) && !is_DNU(temp.info.DeltaUp) &&
656649
(temp.info.Azimuth != uint16DNU)) {
657650

658651
state.rtk_baseline_y_mm = temp.info.DeltaEast * 1e3;
@@ -675,7 +668,6 @@ AP_GPS_SBF::process_message(void)
675668
state.have_gps_yaw = false;
676669
}
677670

678-
#pragma GCC diagnostic pop
679671
break;
680672
}
681673
}

0 commit comments

Comments
 (0)