From 9ceb5a7e2ea37d738aa397a274ab2686e985654d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 3 Oct 2016 11:44:59 +0200 Subject: [PATCH] mavlink: extend status output --- src/modules/mavlink/mavlink_main.cpp | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 6e6291bde3..c136a209ba 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -691,7 +691,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name) default: PX4_ERR("Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n1000000\n", - baud); + baud); return -EINVAL; } @@ -2454,6 +2454,22 @@ Mavlink::display_status() printf("\trx: %.3f kB/s\n", (double)_rate_rx); printf("\trate mult: %.3f\n", (double)_rate_mult); printf("\taccepting commands: %s\n", (accepting_commands()) ? "YES" : "NO"); + printf("\tMAVLink version: %i\n", _protocol_version); + + printf("\ttransport protocol: "); + switch (_protocol) { + case UDP: + printf("UDP (%i)\n", _network_port); + break; + + case TCP: + printf("TCP\n"); + break; + + case SERIAL: + printf("serial (%s @%i)\n", _device_name, _baudrate); + break; + } } int