Elev-8 Commlink Serial Protocol

I'm trying to send data I'm measuring that is different from the data sent to the ground station using Commlink.

I was planning on using Labview to receive this data, log and display it. I've managed to partially decode this serial protocol, but I'm still having trouble.

I can tell that by using the Startpacket/AddPacket/EndPacket/SendPacket there are other pieces of data added (such as start sequence, length, checksum, etc) and I'm able to receive data through putty terminal (that is meaningful, I can see proper changes in the data), but Labview throws errors that make me think my serial settings are incorrect. I was curious what the values for data bits, parity bits, flow control, stop bits etc would be.

Furthermore, if anyone has recommendations how I might simplify my life further using a different method of sending data, I'm all ears!

Thank you,
John

Comments

  • 4 Comments sorted by Date Added Votes
  • Are you trying to decode the full data stream sent by the Elev8?

    The data is sent as 8 bits, no parity, 1 stop bit (almost the universal settings for serial data). Packets are sent with three u16 values as the header (0xAA55, type, length), followed by the data body as a multiple of 16-bit values, and a single 16 bit checksum. The 0xAA55 code lets me more easily find the beginning of a packet if the stream is interrupted. The total packet size is "length" bytes, which includes the extra 8 bytes for the header and checksum. All packets are rounded up to the nearest multiple of two bytes in length, so if you're trying to send a single byte you need to pad it with an extra one. This was done because the checksum runs twice as fast on u16's as on u8's, and almost everything I send is a 2 or 4 byte quantity anyway.

    All the "type" values are in the DoDebugModeOutput() function.

    One caveat to be aware of - I make no attempt whatsoever to guarantee that there is enough room in the serial buffer before I send, so if you exceed the available bandwidth, you'll overwrite and corrupt previous data that's still pending. I've spaced all the data out and made sure the packets are small enough that this doesn't happen in practice. This is what the "phase" value is used for in the DoDebugModeOutput() function - I use a counter that rolls over to keep track of which blob of data I'm sending on this update - it spaces out both the data stream and the CPU usage required to do it. If you're adding a new chunk of data to the stream that's more than a couple bytes you'll need to account for this.

    The simplest way would be to remove an existing packet and take over that "slot" with your data, but use a different "type" value in the header. For example, phase 7 is the "desired quaternion" data, which is probably not needed much. You could send your data instead, or you could even alternate - send your data every other update, so groundstation still shows the desired orientation often enough to be useful.

    Does that all make sense?
  • Thanks for replying! Yes, that makes sense and is quite informative.

    I'm not trying to decode the full data stream, but instead replace it with values that I would like to observe and record in Labview during flight. I have commented out CheckDebugInput() and DoDebugModeOutput() and instead filled in its place:

    if(Radio.Aux1>500 && dataUpdate==1){
    COMMLINK::StartPacket( 0, 4 );
    COMMLINK::AddPacketData(&testVar1, 2 );
    COMMLINK::AddPacketData(&testVar2, 2 );
    COMMLINK::EndPacket();
    COMMLINK::SendPacket(1);
    dataUpdate = 0;
    }

    where dataUpdate is a flag stating that there is new data in testVar1 and testVar2 that has been calculated on another cog ready to be transmitted. Therefore, it should only send data approximately at the rate of the other cog (50Hz). I found that when SendPacket(0) is used to transmit over usb, Putty terminal can read it, but for some reason Labview has a problem. When I connect via the Xbee, Labview is able to read it just fine (which is the important thing as I will not be flying while connected to USB, I just don't know why that problem exists).

    The problem I am now running into is that it seems that the Xbee induces a lot of lag such that it seems there is a backlog of data in some buffer and the data arrives a second or two after an event occurs. I configured the LEDs on-board to turn on when given the same event that is transmitted and the LEDs turn on with no lag and then a second or two later the data appears on the receiving end of the xbee. I noticed this seems to be a problem in Groundstation even when running this with the master code without any of my changes. I also already checked that both xbees are configured correctly to the 57600baud. Are you familiar with such an issue?
  • If you're doing that every frame, you're likely hitting FTDI's magic buffering scheme. The data is partly spread out the way it is to prevent FTDI's driver from clustering it together. If you exceed 62 bytes (I think?) within a certain time frame, they wait until the receive buffer is full (4Kb) before passing it to the host. It's obnoxious.

    And I'm not sure what update rate you're talking about - Elev8's main loop is 250hz, or 200hz for the absolute latest branch from GitHub.

    It's possible you're hitting an XBee buffering issue too - their transparent mode does something similar, so it'd be worth looking through the XCTU (XTCU?) interface for settings to do with latency and buffering. I don't recall what we settled on - it's been a while since I played with the XBees.
  • It is good to know about the FTDI's buffering scheme, that is likely the problem! I'm surprised that is occurring though, I'm only transmitting at maximum 4 bytes (plus the additional bytes for start sequence, length, checksum etc) at 50hz - that's only 4800 bits per second (plus stop bits).

    Sorry, that update rate is describing a new cog I've set up that is able to process sensor data at a rate of 50hz maximum. That sensor data is saved to a global variable and in the main loop, only transmitted when new data is made available. I've found that if I only transmit at a rate of 5-10 hz (still reading from the sensor at 50hz) there doesn't seem to be any lag.
Sign In or Register to comment.