use the proper check to prevent multiple mavlink instances on the same udp port, added warning when different remote than localhost connects to udp

This commit is contained in:
Andreas Antener 2015-12-31 11:50:52 +01:00
parent eff94677a4
commit d39e313768
2 changed files with 13 additions and 6 deletions

View File

@ -1570,14 +1570,20 @@ Mavlink::task_main(int argc, char *argv[])
_datarate = MAX_DATA_RATE;
}
if (Mavlink::instance_exists(_device_name, this)) {
warnx("%s already running", _device_name);
return ERROR;
}
if (get_protocol() == SERIAL) {
warnx("mode: %u, data rate: %d B/s on %s @ %dB", _mode, _datarate, _device_name, _baudrate);
if (Mavlink::instance_exists(_device_name, this)) {
warnx("%s already running", _device_name);
return ERROR;
}
warnx("mode: %u, data rate: %d B/s on %s @ %dB", _mode, _datarate, _device_name, _baudrate);
} else if (get_protocol() == UDP) {
if (Mavlink::get_instance_for_network_port(_network_port) != nullptr) {
warnx("port %d already occupied", _network_port);
return ERROR;
}
warnx("mode: %u, data rate: %d B/s on udp port %hu", _mode, _datarate, _network_port);
}
/* flush stdout in case MAVLink is about to take it over */

View File

@ -1817,6 +1817,7 @@ MavlinkReceiver::receive_thread(void *arg)
if (srcaddr_last->sin_addr.s_addr == htonl(localhost) && srcaddr.sin_addr.s_addr != htonl(localhost)) {
// if we were sending to localhost before but have a new host then accept him
memcpy(srcaddr_last, &srcaddr, sizeof(srcaddr));
PX4_WARN("UDP source addr changed: %s", inet_ntoa(srcaddr.sin_addr));
}
#endif
/* if read failed, this loop won't execute */