dronefleet / mavlink

A Java API for MAVLink communication
MIT License
110 stars 66 forks source link

Unable to get any kind of data from UDP connection #35

Open gadenis opened 4 years ago

gadenis commented 4 years ago

Hi, I have an issue trying to get data with UDP connection to an arducopter >= 3.7.

I'm following these steps:

I set up some wrapper and functions but these steps can be simplified in this way.

---create mavlink connection

Socket socket = new Socket(host, port, false);
socket.setSoTimeout(10000);

MavlinkConnection connection = MavlinkConnection.builder(socket.getInputStream(), socket.getOutputStream())
          .dialect(MavAutopilot.MAV_AUTOPILOT_GENERIC, new StandardDialect())
          .dialect(MavAutopilot.MAV_AUTOPILOT_ARDUPILOTMEGA, newArdupilotmegaDialect()).build();

I never get any kind of message from this connection, I always get timeout. What am I doing wrong?

Is there any issue in the create of mavlink connection? Do I have to do something else to start the mavlink connection in addition to sending the heartbeat and requesting the data stream?

Regarding the connection, I know that this kind of socket constructor is deprecated but I don't know any other way to create a mavlink connection with a UDP socket. Can you suggest a better one?

Many thanks in advance

benbarkay commented 4 years ago

Hi there.

Socket uses TCP, so it's likely failing to communicate with your UDP destination. To make UDP connections you will have to look into DatagramSocket. Since DatagramSocket doesn't provide input/output streams, you will also need to make these for MavlinkConnection to consume. I suggest using PipedInputStream and PipedOutputStream.

Good luck!

gadenis commented 4 years ago

Hi Ben, many thanks for your reply.

I saw your suggestion in the Overview but honestly, I didn't find any way to get PipedInputStream / PipedOutputStream from a DatagramSocket. I also looked for examples but without any success.

Can you please suggest how to get it?

Thanks

benbarkay commented 4 years ago

This is a Java issue but I suppose a ready-made solution would be nice to have because of the friction it creates in terms of starting to use dronefleet/mavlink with existing UDP-based tools like mavproxy. Perhaps this can be implemented in a separate library.

Here's a snippet that might help for now. I only tested this lightly, but it may help with direction:

// The address we listen on to receive packets
SocketAddress localAddress = new InetSocketAddress(
        "127.0.0.1", 1234);

// The address to which we send packets
SocketAddress remoteAddress = new InetSocketAddress(
        "127.0.0.1", 4321);

// The size we use for buffers. 65535 should be able to carry any
// UDP packet of a standard length.
int bufferSize = 65535;

// This binds to the listen address, we can later use this datagram socket
// to receive packets and mark packets with source addresses when sending.
DatagramSocket datagramSocket = new DatagramSocket(localAddress);

// The input/output streams that will be exposed for use. These are what you'd let
// MavlinkConnection use.
PipedInputStream udpIn = new PipedInputStream();
OutputStream udpOut = new OutputStream() {
    // We're buffering data that is written to the output stream,  and then sending the
    // data as a UDP packet when flushing.

    final byte[] buffer = new byte[bufferSize];
    int position = 0;

    @Override
    public void write(int i) throws IOException {
        write(new byte[] { (byte)i }, 0, 1);
    }

    @Override
    public synchronized void write(byte[] b, int off, int len) throws IOException {
        // If the buffer is full, we flush
        if ((position + len) > buffer.length) {
            flush();
        }
        System.arraycopy(b, off, buffer, position, len);
        position += len;
    }

    @Override
    public synchronized void flush() throws IOException {
        DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
        datagramSocket.send(packet);
        position = 0;
    }
};

// We connect `udpIn` to a corresponding PipedOutputStream (`appOut`). Data that we write to
// `appOut` will be available to read from `udpIn`.
// We instantiate/connect here rather than within the reading thread so that `udpIn` can be used immediately.
PipedOutputStream appOut = new PipedOutputStream(udpIn);

// We create a thread pool with 1 thread which we use for receiving packets.
// We keep reading incoming packets and pushing them into `appOut`, so that they
// are available to read from `udpIn`.
ExecutorService service = Executors.newSingleThreadExecutor();
service.execute(() -> {
    try {
        DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize);
        while (!datagramSocket.isClosed()) {
            datagramSocket.receive(packet);
            appOut.write(packet.getData(), packet.getOffset(), packet.getLength());
            appOut.flush();
        }
    } catch (IOException e) {
        e.printStackTrace();
    } finally {
        try {
            appOut.close();
        } catch (IOException e) {
            e.printStackTrace();
        }
        if (!datagramSocket.isClosed()) {
            datagramSocket.close();
        }
        if (!service.isShutdown()) {
            service.shutdown();
        }
    }
});

// We are now left with udpIn and udpOut, with which we can use to read/write

Here's a simple relay example (writes whatever it receives to the remote endpoint):

byte[] receiveBuffer = new byte[bufferSize];
int readLength;
while ((readLength = udpIn.read(receiveBuffer)) != -1) {
    udpOut.write(receiveBuffer, 0, readLength);
    udpOut.flush();
}
OctavianIonel commented 3 years ago

This is a Java issue but I suppose a ready-made solution would be nice to have because of the friction it creates in terms of starting to use dronefleet/mavlink with existing UDP-based tools like mavproxy. Perhaps this can be implemented in a separate library.

Here's a snippet that might help for now. I only tested this lightly, but it may help with direction:

// The address we listen on to receive packets
SocketAddress localAddress = new InetSocketAddress(
        "127.0.0.1", 1234);

// The address to which we send packets
SocketAddress remoteAddress = new InetSocketAddress(
        "127.0.0.1", 4321);

// The size we use for buffers. 65535 should be able to carry any
// UDP packet of a standard length.
int bufferSize = 65535;

// This binds to the listen address, we can later use this datagram socket
// to receive packets and mark packets with source addresses when sending.
DatagramSocket datagramSocket = new DatagramSocket(localAddress);

// The input/output streams that will be exposed for use. These are what you'd let
// MavlinkConnection use.
PipedInputStream udpIn = new PipedInputStream();
OutputStream udpOut = new OutputStream() {
    // We're buffering data that is written to the output stream,  and then sending the
    // data as a UDP packet when flushing.

    final byte[] buffer = new byte[bufferSize];
    int position = 0;

    @Override
    public void write(int i) throws IOException {
        write(new byte[] { (byte)i }, 0, 1);
    }

    @Override
    public synchronized void write(byte[] b, int off, int len) throws IOException {
        // If the buffer is full, we flush
        if ((position + len) > buffer.length) {
            flush();
        }
        System.arraycopy(b, off, buffer, position, len);
        position += len;
    }

    @Override
    public synchronized void flush() throws IOException {
        DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
        datagramSocket.send(packet);
        position = 0;
    }
};

// We connect `udpIn` to a corresponding PipedOutputStream (`appOut`). Data that we write to
// `appOut` will be available to read from `udpIn`.
// We instantiate/connect here rather than within the reading thread so that `udpIn` can be used immediately.
PipedOutputStream appOut = new PipedOutputStream(udpIn);

// We create a thread pool with 1 thread which we use for receiving packets.
// We keep reading incoming packets and pushing them into `appOut`, so that they
// are available to read from `udpIn`.
ExecutorService service = Executors.newSingleThreadExecutor();
service.execute(() -> {
    try {
        DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize);
        while (!datagramSocket.isClosed()) {
            datagramSocket.receive(packet);
            appOut.write(packet.getData(), packet.getOffset(), packet.getLength());
            appOut.flush();
        }
    } catch (IOException e) {
        e.printStackTrace();
    } finally {
        try {
            appOut.close();
        } catch (IOException e) {
            e.printStackTrace();
        }
        if (!datagramSocket.isClosed()) {
            datagramSocket.close();
        }
        if (!service.isShutdown()) {
            service.shutdown();
        }
    }
});

// We are now left with udpIn and udpOut, with which we can use to read/write

Here's a simple relay example (writes whatever it receives to the remote endpoint):

byte[] receiveBuffer = new byte[bufferSize];
int readLength;
while ((readLength = udpIn.read(receiveBuffer)) != -1) {
    udpOut.write(receiveBuffer, 0, readLength);
    udpOut.flush();
}

Hello, I have some questions: 1) In this example with UDP, where are you using the Mavlink specific classes? Like MavlinkConnection? Maybe an example with sending and another one with receiving will make a lot of sense. 2) I am not sure to have understood exactly how it works Mavlink. It shouldn't be similar to how we serialize/deserialize JSON with Gson or Jettison or whatever?

benbarkay commented 3 years ago

@OctavianIonel

As for your first question, you would use udpIn and udpOut to construct a MavlinkConnection like you would with a Socket's input/output streams:

MavlinkConnection connection = MavlinkConnection.create(udpIn, udpOut);

You can then use connection as shown in the README examples.

To answer your second question, not exactly. Mavlink is not a generic object format like JSON is. It includes a generic packet format, but that's about where the similarity to JSON ends. To understand a message, you must resolve it against a specific dialect. I have tried to make this implementation as closely resembling to JSON as possible by allowing one to implement a dialect using reflection, but it's impossible to implement in the way that GSON can for JSON.

Additionally, there are some nuances related to the protocol which you would have to implement, which are related to the current state of the connection, such as sequencing and dialect selection.

If you want to implement these yourself, and deal with something more similar to json serialization/deserialization, then you can use MavlinkPacketReader to parse packets, and then use ReflectionPayloadDeserializer to deserialize it into an actual message object. You can take a look at the implementation of MavlinkConnection to see how all of that works.

OctavianIonel commented 3 years ago

@OctavianIonel

As for your first question, you would use udpIn and udpOut to construct a MavlinkConnection like you would with a Socket's input/output streams:

MavlinkConnection connection = MavlinkConnection.create(udpIn, udpOut);

You can then use connection as shown in the README examples.

To answer your second question, not exactly. Mavlink is not a generic object format like JSON is. It includes a generic packet format, but that's about where the similarity to JSON ends. To understand a message, you must resolve it against a specific dialect. I have tried to make this implementation as closely resembling to JSON as possible by allowing one to implement a dialect using reflection, but it's impossible to implement in the way that GSON can for JSON.

Additionally, there are some nuances related to the protocol which you would have to implement, which are related to the current state of the connection, such as sequencing and dialect selection.

If you want to implement these yourself, and deal with something more similar to json serialization/deserialization, then you can use MavlinkPacketReader to parse packets, and then use ReflectionPayloadDeserializer to deserialize it into an actual message object. You can take a look at the implementation of MavlinkConnection to see how all of that works.

@benbarkay thanks for your answer. As to close the loop and try it locally, do you know how can I configure a mavlink server in java? Thanks

benbarkay commented 3 years ago

@OctavianIonel I've been using ardupilot's simulators successfully. If you want to implement your own server then you can simply use this library with a ServerSocket or a DatagramSocket. I won't get into detail of how to do these, as they are off-topic here, and there are many resources that do just that online.

OctavianIonel commented 3 years ago

Hi @benbarkay I have configured a TCP server in python and with the client code example from your readme it works (I can get the heartbeat on the server). The UDP/TCP server is in python, very simple:

from pymavlink import mavutil
# Start a connection listening to a UDP port
connection = mavutil.mavlink_connection('udpin:localhost:14540')
# connection = mavutil.mavlink_connection('tcpin:localhost:14540')
# Wait for the first heartbeat
#   This sets the system and component ID of remote system for the link
print('waiting for heartbeat')
connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (connection.target_system, connection.target_system))
while True:
    msg = connection.recv_match(blocking=True)
    print('received system status', msg.type)

Now I am dealing with the UDP client side. My client code is the following, but nothing is received on the server side:

   int systemId = 255;
    int componentId = 0;

    //UDP
    try {
        // The address we listen on to receive packets
        SocketAddress localAddress = new InetSocketAddress(
                "localhost", 1234);

        // The address to which we send packets
        SocketAddress remoteAddress = new InetSocketAddress(
                "localhost", 14540);

        // The size we use for buffers. 65535 should be able to carry any
        // UDP packet of a standard length.
        int bufferSize = 65535;

        // This binds to the listen address, we can later use this datagram socket
        // to receive packets and mark packets with source addresses when sending.
        DatagramSocket datagramSocket = new DatagramSocket(localAddress);
        PipedInputStream udpIn = new PipedInputStream();

        OutputStream udpOut = new OutputStream() {
            // We're buffering data that is written to the output stream,  and then sending the
            // data as a UDP packet when flushing.

            final byte[] buffer = new byte[bufferSize];
            int position = 0;

            @Override
            public void write(int i) throws IOException {
                write(new byte[] { (byte)i }, 0, 1);
            }

            @Override
            public synchronized void write(byte[] b, int off, int len) throws IOException {
                // If the buffer is full, we flush
                if ((position + len) > buffer.length) {
                    flush();
                }
                System.arraycopy(b, off, buffer, position, len);
                position += len;
            }

            @Override
            public synchronized void flush() throws IOException {
                DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
                datagramSocket.send(packet);
                position = 0;
            }
        };

        // We connect `udpIn` to a corresponding PipedOutputStream (`appOut`). Data that we write to
       // `appOut` will be available to read from `udpIn`.
       // We instantiate/connect here rather than within the reading thread so that `udpIn` can be used immediately.
        PipedOutputStream appOut = new PipedOutputStream(udpIn);

         // We create a thread pool with 1 thread which we use for receiving packets.
        // We keep reading incoming packets and pushing them into `appOut`, so that they
        // are available to read from `udpIn`.
        ExecutorService service = Executors.newSingleThreadExecutor();
        service.execute(() -> {
            try {
                DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize);
                while (!datagramSocket.isClosed()) {
                    datagramSocket.receive(packet);
                    appOut.write(packet.getData(), packet.getOffset(), packet.getLength());
                    appOut.flush();
                }
            } catch (IOException e) {
                e.printStackTrace();
            } finally {
                try {
                    appOut.close();
                } catch (IOException e) {
                    e.printStackTrace();
                }
                if (!datagramSocket.isClosed()) {
                    datagramSocket.close();
                }
                if (!service.isShutdown()) {
                    service.shutdown();
                }
            }
        });

        Heartbeat heartbeat = Heartbeat.builder()
                .type(MavType.MAV_TYPE_GCS)
                .autopilot(MavAutopilot.MAV_AUTOPILOT_INVALID)
                .systemStatus(MavState.MAV_STATE_UNINIT)
                .mavlinkVersion(3)
                .build();
        MavlinkConnection connection = MavlinkConnection.create(udpIn, udpOut);
        connection.send2(systemId, componentId, heartbeat);
    } catch (IOException e) {
        e.printStackTrace();
    }
OctavianIonel commented 3 years ago

@benbarkay I tried the code above with the UDP and it is not working, what could be the issue? Thanks for your help!

benbarkay commented 3 years ago

In terms of reading there should not be an issue. Try calling udpOut.flush() right after connection.send, so that packets are sent out immediately, perhaps that is preventing you from seeing traffic.

On Mon, Apr 19, 2021, 18:19 OctavianIonel @.***> wrote:

@benbarkay https://github.com/benbarkay I tried the code above with the UDP and it is not working, what could be the issue? Thanks for your help!

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/dronefleet/mavlink/issues/35#issuecomment-822552620, or unsubscribe https://github.com/notifications/unsubscribe-auth/AA4DXUU2BWOPQZ4ABN7I6YDTJRCWRANCNFSM4JCI23AQ .

OctavianIonel commented 3 years ago

Indeed @benbarkay this was the problem, now it works! Many thanks!

zeev-mindali commented 2 years ago

@OctavianIonel did you mange to get it to work? i also looking for udp solution with no success at this time...

zeev-mindali commented 2 years ago

@benbarkay could you assist to a friend from israel, how to achive udp connection?

OctavianIonel commented 2 years ago

@OctavianIonel did you mange to get it to work? i also looking for udp solution with no success at this time...

Yes, I made it work with udp

zeev-mindali commented 2 years ago

@OctavianIonel could you share the code please? i trying to send commands to herelink rc which works on udp port 15442

benbarkay commented 2 years ago

@benbarkay could you assist to a friend from israel, how to achive udp connection?

What have you been trying so far? When it fails, what exceptions/errors/logs are you getting in the JVM/mavproxy/other software in the loop?

zeev-mindali commented 2 years ago

sent an explation in issue #70

zeev-mindali commented 2 years ago

@OctavianIonel can you share the code for connection?

OctavianIonel commented 2 years ago

@zeev-mindali I think you should send the heartbeat repetitively. Wrap that in a timer for example. In your code you are sending it only once.

zeev-mindali commented 2 years ago

@OctavianIonel in tcp i getting and sending heart beat. i using herelink RC, and i getting confused when i need UDP in and when UDP out. should them both need to point to herelink server or one for RC and one for computer?

zeev-mindali commented 2 years ago

@OctavianIonel it stuck on connection.next() any suggestion?

moralkerim commented 2 years ago

This is a Java issue but I suppose a ready-made solution would be nice to have because of the friction it creates in terms of starting to use dronefleet/mavlink with existing UDP-based tools like mavproxy. Perhaps this can be implemented in a separate library.

Here's a snippet that might help for now. I only tested this lightly, but it may help with direction:

// The address we listen on to receive packets
SocketAddress localAddress = new InetSocketAddress(
        "127.0.0.1", 1234);

// The address to which we send packets
SocketAddress remoteAddress = new InetSocketAddress(
        "127.0.0.1", 4321);

// The size we use for buffers. 65535 should be able to carry any
// UDP packet of a standard length.
int bufferSize = 65535;

// This binds to the listen address, we can later use this datagram socket
// to receive packets and mark packets with source addresses when sending.
DatagramSocket datagramSocket = new DatagramSocket(localAddress);

// The input/output streams that will be exposed for use. These are what you'd let
// MavlinkConnection use.
PipedInputStream udpIn = new PipedInputStream();
OutputStream udpOut = new OutputStream() {
    // We're buffering data that is written to the output stream,  and then sending the
    // data as a UDP packet when flushing.

    final byte[] buffer = new byte[bufferSize];
    int position = 0;

    @Override
    public void write(int i) throws IOException {
        write(new byte[] { (byte)i }, 0, 1);
    }

    @Override
    public synchronized void write(byte[] b, int off, int len) throws IOException {
        // If the buffer is full, we flush
        if ((position + len) > buffer.length) {
            flush();
        }
        System.arraycopy(b, off, buffer, position, len);
        position += len;
    }

    @Override
    public synchronized void flush() throws IOException {
        DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
        datagramSocket.send(packet);
        position = 0;
    }
};

// We connect `udpIn` to a corresponding PipedOutputStream (`appOut`). Data that we write to
// `appOut` will be available to read from `udpIn`.
// We instantiate/connect here rather than within the reading thread so that `udpIn` can be used immediately.
PipedOutputStream appOut = new PipedOutputStream(udpIn);

// We create a thread pool with 1 thread which we use for receiving packets.
// We keep reading incoming packets and pushing them into `appOut`, so that they
// are available to read from `udpIn`.
ExecutorService service = Executors.newSingleThreadExecutor();
service.execute(() -> {
    try {
        DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize);
        while (!datagramSocket.isClosed()) {
            datagramSocket.receive(packet);
            appOut.write(packet.getData(), packet.getOffset(), packet.getLength());
            appOut.flush();
        }
    } catch (IOException e) {
        e.printStackTrace();
    } finally {
        try {
            appOut.close();
        } catch (IOException e) {
            e.printStackTrace();
        }
        if (!datagramSocket.isClosed()) {
            datagramSocket.close();
        }
        if (!service.isShutdown()) {
            service.shutdown();
        }
    }
});

// We are now left with udpIn and udpOut, with which we can use to read/write

Here's a simple relay example (writes whatever it receives to the remote endpoint):

byte[] receiveBuffer = new byte[bufferSize];
int readLength;
while ((readLength = udpIn.read(receiveBuffer)) != -1) {
    udpOut.write(receiveBuffer, 0, readLength);
    udpOut.flush();
}

Hi, I can receive messages with this example but can't seem to send a heartbeat to autopilot. I could be able to send heartbeat by tcp. What might be the problem? Would be great if you can help. Thanks.

swagatampanda3894 commented 8 months ago

after implement your code i got java.net.BindException: bind failed: EADDRNOTAVAIL (Cannot assign requested address) error ,

I have provide the android ip address , and port

gremsyQuanLe commented 8 months ago

show your udp connection code so we can help ???

swagatampanda3894 commented 8 months ago

AppExecutors.getInstance().getDiskIO().execute(() -> { try {

            // The address we listen on to receive packets
            SocketAddress localAddress = new InetSocketAddress(
                    "192.168.144.12", UDP_PORT);

           // The address to which we send packets
            SocketAddress remoteAddress = new InetSocketAddress(
                    "192.168.144.12", UDP_PORT);

            // The size we use for buffers. 65535 should be able to carry any
            // UDP packet of a standard length.
            int bufferSize = 65535;

            // This binds to the listen address, we can later use this datagram socket
            // to receive packets and mark packets with source addresses when sending.
            DatagramSocket datagramSocket = new DatagramSocket(localAddress);

               // The input/output streams that will be exposed for use. These are what you'd let
               // MavlinkConnection use.
            PipedInputStream udpIn = new PipedInputStream();
            OutputStream udpOut = new OutputStream() {
                // We're buffering data that is written to the output stream,  and then sending the
                // data as a UDP packet when flushing.

                final byte[] buffer = new byte[bufferSize];
                int position = 0;

                @Override
                public void write(int i) throws IOException {
                    write(new byte[] { (byte)i }, 0, 1);
                }

                @Override
                public synchronized void write(byte[] b, int off, int len) throws IOException {
                    // If the buffer is full, we flush
                    if ((position + len) > buffer.length) {
                        flush();
                    }
                    System.arraycopy(b, off, buffer, position, len);
                    position += len;
                }

                @Override
                public synchronized void flush() throws IOException {
                    DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
                    datagramSocket.send(packet);
                    position = 0;
                }
            };

// We connect udpIn to a corresponding PipedOutputStream (appOut). Data that we write to // appOut will be available to read from udpIn. // We instantiate/connect here rather than within the reading thread so that udpIn can be used immediately. PipedOutputStream appOut = new PipedOutputStream(udpIn);

// We create a thread pool with 1 thread which we use for receiving packets. // We keep reading incoming packets and pushing them into appOut, so that they // are available to read from udpIn. ExecutorService service = Executors.newSingleThreadExecutor(); service.execute(() -> { try { DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize); while (!datagramSocket.isClosed()) { datagramSocket.receive(packet); Toast.makeText(getApplicationContext(),"PACKETRECEIVED "+ packet.getLength(),Toast.LENGTH_SHORT).show(); appOut.write(packet.getData(), packet.getOffset(), packet.getLength()); appOut.flush(); } } catch (IOException e) { Log.e("ERRROR ","ERRORS1 "+ e); e.printStackTrace(); } finally { try { appOut.close(); } catch (IOException e) { e.printStackTrace(); } if (!datagramSocket.isClosed()) { datagramSocket.close(); } if (!service.isShutdown()) { service.shutdown(); } } });

            // We are now left with udpIn and udpOut, with which we can use to read/write

            byte[] receiveBuffer = new byte[bufferSize];
            int readLength;
            while ((readLength = udpIn.read(receiveBuffer)) != -1) {
                udpOut.write(receiveBuffer, 0, readLength);
                udpOut.flush();
            }

        } catch (IOException e){
            Log.e("ERRROR ","ERRORS "+ e);

        }

this above code

swagatampanda3894 commented 8 months ago

The issue in port case , I am confused that in port that source and destination,

MrBoxed commented 3 months ago

Here is the working UDP Connection sample code

private void UDPConnection(){

// ConnectionDataClass holding the IP & PORT of connection
    ConnectionData udpDataRef = getSocketData();
    if (udpDataRef == null){
            return;
    }

        // The address we listen on to receive/send packets
        SocketAddress remoteAddress = new InetSocketAddress(udpDataRef.getIpAddress(), udpDataRef.getPort());

        // The size we use for buffers. 65535 should be able to carry any
        // UDP packet of a standard length.
        int bufferSize = 65535;

        try {
            // This binds to the listen address, we can later use this datagram socket
            // to receive packets and mark packets with source addresses when sending.
            DatagramSocket udpSocket = new DatagramSocket();
            udpSocket.connect(remoteAddress);

            PipedInputStream udpIn = new PipedInputStream();

            OutputStream udpOut = new OutputStream() {

                final byte[] buffer = new byte[bufferSize];
                int position = 0;

                @Override
                public void write(int b) throws IOException {

                    write(new byte[]{(byte) b}, 0, 1);
                }

                @Override
                public void write(byte[] b, int off, int len) throws IOException {

                    // if the buffer is full, we flush
                    if ((position + len) > (buffer.length)) {
                        flush();
                    }
                    System.arraycopy(b, off, buffer, position, len);
                    position += len;
                }

                @Override
                public void flush() throws IOException {
                    DatagramPacket packet = new DatagramPacket(buffer, 0, position, remoteAddress);
                    udpSocket.send(packet);
                    position = 0;
                }
            };

            // We connect `udpIn` to a corresponding PipedOutputStream (`appOut`). Data that we write to
            // `appOut` will be available to read from `udpIn`.
            // We instantiate/connect here rather than within the reading thread so that `udpIn` can be used immediately.
            PipedOutputStream appOut = new PipedOutputStream(udpIn);

            ExecutorService service = Executors.newSingleThreadExecutor();
            service.execute(() -> {
                try {
                    DatagramPacket packet = new DatagramPacket(new byte[bufferSize], bufferSize);
                    while (!udpSocket.isClosed()) {
                        udpSocket.receive(packet);
                        appOut.write(packet.getData(), packet.getOffset(), packet.getLength());
                        appOut.flush();
                    }
                } catch (IOException e) {
                    e.printStackTrace();
                } finally {
                    try {
                        appOut.close();
                    } catch (IOException e) {
                        e.printStackTrace();
                    }
                    if (!udpSocket.isClosed()) {
                        udpSocket.close();
                    }
                    if (!service.isShutdown()) {
                        service.shutdown();
                    }
                }
            });

            // if udp connection was able to connect with the port,
            // then set the state of the connection to true
            if (udpSocket.isConnected()) {

                mavlinkConnection = MavlinkConnection.create(udpIn, udpOut);
                mavlinkmessage = null;

                while((mavlinkmessage = mavlinkConnection.next()) != null){

                    if (message.getPayload() instanceof Heartbeat heartbeat) {}
                }

            } else {
                udpSocket.close();
                Log.d("CONNECTION", "SOCKET FAILED TO CONNECT WITH MAVLINK");
                return;
            }

            // closing connection : because we are out of loop at this point
            udpSocket.close();

        } catch (IOException e) {

            Log.e("Connection", "socket timeout: UDP mavlink service " + e.getMessage());
            mavlinkConnection = null;
        }

}