AP_GPS: Report when SBF errors change
This commit is contained in:
parent
44d0f7b2a1
commit
b1a3e0a537
@ -368,6 +368,10 @@ AP_GPS_SBF::process_message(void)
|
|||||||
{
|
{
|
||||||
const msg4014 &temp = sbf_msg.data.msg4014u;
|
const msg4014 &temp = sbf_msg.data.msg4014u;
|
||||||
RxState = temp.RxState;
|
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;
|
RxError = temp.RxError;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user