@@ -590,14 +590,13 @@ 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
597596#pragma GCC diagnostic push
598597#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
599598 if (((temp.Error & errorBits) == 0 )
600- && (temp.Cov_HeadHead != floatDNU) ) {
599+ && ! is_DNU (temp.Cov_HeadHead ) {
601600#pragma GCC diagnostic pop
602601 state.gps_yaw_accuracy = sqrtf (temp.Cov_HeadHead );
603602 state.have_gps_yaw_accuracy = true ;
@@ -633,7 +632,6 @@ AP_GPS_SBF::process_message(void)
633632 const msg4028 &temp = sbf_msg.data .msg4028u ;
634633
635634 // just breakout any consts we need for Do Not Use (DNU) reasons
636- constexpr double doubleDNU = -2e-10 ;
637635 constexpr uint16_t uint16DNU = 65535 ;
638636
639637 check_new_itow (temp.TOW , sbf_msg.length );
@@ -652,7 +650,7 @@ AP_GPS_SBF::process_message(void)
652650 state.rtk_age_ms = (temp.info .CorrAge != 65535 ) ? ((uint32_t )temp.info .CorrAge ) * 10 : 0 ;
653651
654652 // 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 ) &&
653+ if (! is_DNU (temp.info .DeltaEast ) && ! is_DNU (temp.info .DeltaNorth ) && ! is_DNU (temp.info .DeltaUp ) &&
656654 (temp.info .Azimuth != uint16DNU)) {
657655
658656 state.rtk_baseline_y_mm = temp.info .DeltaEast * 1e3 ;
0 commit comments