C++ Asio Pixhawk/Computer UART RX issues

Hello, My plan is to hopefully end up being able to manipulate waypoints through the mavlink protocol. I am trying to do this using the official Mavlink C library with asio for managing the serial/UART connection. I’m a complete noob when it comes to UART, mind you, but I feel like I got to a point, where I can’t really proceed. My reference is the uart example from the Mavlink repo.

I have a pixhawk2 flight controller that talks with my computer (macOS/Win64) through a pair of mRo 433 MHz SiK antennas. Currently my program sends nothing, I am just reading from the port.

BeingRX() initially calls when the port is opened from my computer:

void Serial::BeginRX()
{
    // Owner of this Serial (port) is my "Bridge"
    if(GetOwner() == nullptr)
    {
        throw;
    }
    
    Listen();

    io_service.run();
}

Listen() looks for anything happening on the line:

void Serial::Listen()
{
    // buffer size = 1 for STX
    const size_t nbyte = 1;

    // shared_ptr for moving into other object if needed in future
    std::shared_ptr<std::array<uint8_t, nbyte>> buffer = std::make_shared<std::array<uint8_t, nbyte>>();

    asio::async_read(port,
                    asio::buffer(*buffer, nbyte),
                    [this, buffer](const asio::error_code& ec, std::size_t bytes_transferred)
                    {
                        GetOwner()->ReadHandle_Listen(ec, bytes_transferred, buffer);

                        if (GetOwner()->bHasReceivedGoodRX())
                        {
                            // Parse data when this actually works
                        }
                        else
                        {
                            // Otherwise keep listening
                            Listen();
                        }
                    });

#ifdef DEBUG_COMMS
    std::cout << "Listen() on " << GetPortID() << std::endl;
#endif
}

This is my Listen read handle, what happens when data is received:

void MavlinkBridge::ReadHandle_Listen(const asio::error_code& error_code, std::size_t bytes_transferred, std::shared_ptr<std::array<uint8_t, 1>> buffer)
{
#ifdef DEBUG_COMMS
    MavlinkBridgeDebug::DebugMsg("Port received message");
#endif
    if ( (error_code) || (bytes_transferred < 1) )
    {
#ifdef DEBUG_COMMS 
    MavlinkBridgeDebug::DebugMsg("  Message received is faulty.");
#endif
        return;
    }
    
    mavlink_message_t message;
    mavlink_status_t* new_status = new mavlink_status_t;

    uint8_t b_msg_has_been_received = false;
    uint8_t b_message_is_good = false;

    const unsigned int device_mavlink_version = mavlink_get_proto_version((*buffer)[0]);

    b_message_is_good = mavlink_parse_char(MAVLINK_COMM_1, (*buffer)[0], &message, new_status);

    if ( (last_status->packet_rx_drop_count != new_status->packet_rx_drop_count) ) // TODO: && debug )
    {
        std::cout << "Error reading: Packet loss." << std::endl;
    }

    if (b_message_is_good)
    {   
        // Never happens
        b_has_received_good_RX = true;

#ifdef DEBUG_COMMS
        MavlinkBridgeDebug::DebugMsg("  Received good message.");
#endif
    }
    else
    {
        b_has_received_good_RX = false;
#ifdef DEBUG_COMMS
        MavlinkBridgeDebug::DebugMsg("  Received bad message.");
#endif
    }
#ifdef DEBUG_COMMS
        std::cout << "    " << (*buffer)[0] << std::endl;
#endif
}

I tried utilising the helper functions from the mavlink library but ultimately I didn’t understand how they should be utilised outside the example. It looks like the whole mavlink uart example got the whole message from reading one single char on the _read_port() function

Running the program I constantly get “bad” messsages. This is just a snippet of the above debug messages (With the “character” being from (*buffer)[0]), running on a Mac:

Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    "
Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    =
Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    xfd
Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    xe4
Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    x8c
Listen() on /dev/tty.usbserial-DO01HWLH
[DEBUG] MavlinkBridge: Port received message
[DEBUG] MavlinkBridge:   Received bad message.
    xfd

I’m a bit lost, and I hope that perhaps someone could perhaps deduct what I am doing wrong.
I feel like I double checked the baud rate more than a few times now. The pixhawk baud rate is set to the default 1200, and so is the baud rate on the computer.

Regards

I managed to receive messages that return true using mavlink_parse_char() now. However, I suspect something is off with the way the uint8_t data type is being handled.

My read handle:

void MavlinkBridge::ReadHandle_Listen(const asio::error_code& error_code, std::size_t bytes_transferred, uint8_t byte)
{
    if ( (error_code) || (bytes_transferred < 1) )
    {
#ifdef DEBUG_COMMS
    MavlinkBridgeDebug::DebugMsg("  Message received is faulty.");
#endif
        return;
    }

    mavlink_message_t message;
    mavlink_status_t* new_status = new mavlink_status_t;

    uint8_t b_msg_has_been_received = false;
    uint8_t b_message_is_good = false;

    const unsigned int device_mavlink_version = mavlink_get_proto_version(byte);

    b_message_is_good = mavlink_parse_char(MAVLINK_COMM_0, byte, &message, new_status);

    if ( last_status->packet_rx_drop_count != new_status->packet_rx_drop_count )
    {
        std::cout << "Error reading: Packet loss." << std::endl;
    }
    
    if (b_message_is_good)
    {   
        

#ifdef DEBUG_COMMS
        if (last_status->packet_rx_drop_count != new_status->packet_rx_drop_count)
		{
			MavlinkBridgeDebug::DebugMsg("ERROR: DROPPED ", new_status->packet_rx_drop_count, "PACKETS");
		}

        MavlinkBridgeDebug::DebugMsg("  Received good message.");
        MavlinkBridgeDebug::DebugMsg("  ", "Buffer Character: ", byte);

        MavlinkBridgeDebug::DebugMsg("     Mes ID: ", message.msgid);
        MavlinkBridgeDebug::DebugMsg("     Sys ID: ", message.sysid);
        MavlinkBridgeDebug::DebugMsg("    Comp ID: ", message.compid);
#endif
        last_status.reset(new_status);
        //std::array<uint8_t, MAVLINK_MAX_PACKET_LEN> buffer;
        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];

        // Check message write length
        unsigned int msg_length = mavlink_msg_to_send_buffer(buffer, &message);


        if (msg_length > MAVLINK_MAX_PACKET_LEN)
        {
#ifdef DEBUG_COMMS
            MavlinkBridgeDebug::DebugMsg("Message received too long");
#endif
            return;
        }
        else
        {
#ifdef DEBUG_COMMS
            for (const auto& msg_byte : buffer)
            {
                std::cout << msg_byte;
            }
            std::cout << std::endl;
#endif
            b_has_received_good_RX = true;
        }

        
    }
    else
    {
        b_has_received_good_RX = false;
#ifdef DEBUG_COMMSNO
        MavlinkBridgeDebug::DebugMsg("  Received bad message.");
#endif
    }
}

My ::DebugMsg() prints std::cout recursively so it should be like using std::cout.

A sample debug run of a good message outputs:

[DEBUG] MavlinkBridge:   Received good message.
[DEBUG] MavlinkBridge:   Buffer Character: xe6
[DEBUG] MavlinkBridge:      Mes ID: 30
[DEBUG] MavlinkBridge:      Sys ID: x01
[DEBUG] MavlinkBridge:     Comp ID: x01
xfdx1cx00x00	x01x01x1ex00x00QVx11x00ex7fx1dxbdxb7xe7xf2xbc5Gx9bxbf[xd0x96xbaxa1xeaxaaxb9#8N:xa0xe60xebxbfxefx01x00x00x00x00x00x00x00x00x00x00x00@xebxbfxefxfex7fx00x00x00x00x00x00x01x00x00x00xc0|x8ax80xffx7fx00x00xa0xebxbfxefxfex7fx00x008xb2x13x00x01x00x00x00x00x00x00x00x01x00x00x00xc0|x8ax80xffx7fx00x00 APx00x01x00x00x00bxedxbfxefxfex7fx00x00x01x00x00x00x00x00x00x00x00x00x00x00x00x00x00x00x01x00x00x00x00x00x00x00xe0@Px00x01x00x00x00bxedxbfxefxfex7fx00x00xe8xecxbfxefxfex7fx00x00x90xecxbfxefxfex7fx00x00xc8xebxbfxefxfex7fx00x00xf8xecxbfxefxfex7fx00x00 APx00x01x00x00x00x00xecxbfxefxfex7fx00x00xa5xb1x13x00x01x00x00x00x98xecxbfxefxfex7fx00x00 APx00x01x00x00x00xf8xecxbfxefxfex7fx00x00xf8xecxbfxefxfex7fx00x00x90xecxbfxefxfex7fx00x00xe8xecxbfxefxfex7fx00x00x90xecxbfxefxfex7fx00x00

My question is, is it normal to see uint8_t’s being output as hexadecimals? I discussed it with a few people, and they have never seen uint8_t’s getting displayed as \x00 like they do in my debugger, or as x00 when they get output by std::cout.
Sometimes the buffer byte gets output as a single character, and the uint32_t:24 message ID always gets output as a normal integer.

I use macOS (Intel), VSCode with Clang13 and c++17.