diff --git a/msg/radio_status.msg b/msg/radio_status.msg index 3372abd10f..c57c82b5e3 100644 --- a/msg/radio_status.msg +++ b/msg/radio_status.msg @@ -10,4 +10,4 @@ uint8 noise # background noise level uint8 remote_noise # remote background noise level uint16 rxerrors # receive errors -uint16 fixed # count of error corrected packets +uint16 fix # count of error corrected packets diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index dfd45800bb..9bc04b4c72 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2807,7 +2807,7 @@ Mavlink::display_status() printf("\t noise:\t%d\n", _rstatus.noise); printf("\t remote noise:\t%u\n", _rstatus.remote_noise); printf("\t rx errors:\t%u\n", _rstatus.rxerrors); - printf("\t fixed:\t%u\n", _rstatus.fixed); + printf("\t fixed:\t%u\n", _rstatus.fix); break; case telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_USB: diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 62b7931256..de477c9ef8 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1504,7 +1504,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) status.noise = rstatus.noise; status.remote_noise = rstatus.remnoise; status.rxerrors = rstatus.rxerrors; - status.fixed = rstatus.fixed; + status.fix = rstatus.fixed; _mavlink->update_radio_status(status);