Browse Source

AP_GPS: Report when SBF errors change

mission-4.1.18
Michael du Breuil 7 years ago committed by WickedShell
parent
commit
b1a3e0a537
  1. 4
      libraries/AP_GPS/AP_GPS_SBF.cpp

4
libraries/AP_GPS/AP_GPS_SBF.cpp

@ -368,6 +368,10 @@ AP_GPS_SBF::process_message(void) @@ -368,6 +368,10 @@ AP_GPS_SBF::process_message(void)
{
const msg4014 &temp = sbf_msg.data.msg4014u;
RxState = temp.RxState;
if ((RxError & RX_ERROR_MASK) != (temp.RxError & RX_ERROR_MASK)) {
gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF error changed (0x%08x/0x%08x)", state.instance + 1,
RxError & RX_ERROR_MASK, temp.RxError & RX_ERROR_MASK);
}
RxError = temp.RxError;
break;
}

Loading…
Cancel
Save