diff --git a/libraries/SITL/examples/JSON/MATLAB/SITL_connector.m b/libraries/SITL/examples/JSON/MATLAB/SITL_connector.m index 5c1a4f0a39..6957f6b215 100644 --- a/libraries/SITL/examples/JSON/MATLAB/SITL_connector.m +++ b/libraries/SITL/examples/JSON/MATLAB/SITL_connector.m @@ -88,7 +88,6 @@ while true if ~connected % use port -1 to indicate connection to address of last recv pkt - pnet(u,'udpconnect',"",-1); connected = true; [ip, port] = pnet(u,'gethost'); fprintf('Connected to %i.%i.%i.%i:%i\n',ip,port)