diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index 3283c4a5d1..4643ec8263 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -232,7 +232,9 @@ void _usage(void) printf("\t -B /dev/ttyS1\n"); printf("\t-tcp: -C tcp:192.168.2.15:1243:wait\n"); printf("\t -A tcp:11.0.0.2:5678\n"); - printf("\t -A udp:11.0.0.2:5678\n"); + printf("\t -A udp:11.0.0.2:14550\n"); + printf("\t -A udp:11.0.0.255:14550:bcast\n"); + printf("\t -A udpin:0.0.0.0:14550\n"); printf("\t-custom log path:\n"); printf("\t --log-directory /var/APM/logs\n"); printf("\t -l /var/APM/logs\n"); diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index 7c6984b4ba..3d3e9ba8a5 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -312,6 +312,10 @@ void UARTDriver::_udp_start_connection(void) */ void UARTDriver::_udpin_start_connection(void) { + bool bcast = (_flag && strcmp(_flag, "bcast") == 0); + if (bcast) { + AP_HAL::panic("Can't combine udpin with bcast"); + } _device = new UDPDevice(_ip, _base_port, false, true); _connected = _device->open(); _device->set_blocking(false);