forked from Archive/PX4-Autopilot
MAVLink: Send USB telem status
This commit is contained in:
parent
0fe2bb5886
commit
85ad5a622a
|
@ -700,6 +700,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
|
|||
_is_usb_uart = true;
|
||||
/* USB has no baudrate, but use a magic number for 'fast' */
|
||||
_baudrate = 2000000;
|
||||
_rstatus.type = telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_USB;
|
||||
}
|
||||
|
||||
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN)
|
||||
|
@ -2096,8 +2097,12 @@ Mavlink::display_status()
|
|||
printf("3DR RADIO\n");
|
||||
break;
|
||||
|
||||
case telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_USB:
|
||||
printf("USB CDC\n");
|
||||
break;
|
||||
|
||||
default:
|
||||
printf("UNKNOWN RADIO\n");
|
||||
printf("GENERIC LINK OR RADIO\n");
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue