Dear Ian,
your reply gave me further motivation to look into the issue. And you are right - DJI Goggles RE with OcuSync Air Unit also supports MAVLink. How DJI solved supporting MSP and MAVLink at the same time is quite clever and took me some time to understand. The difficulty lies in the used baud rates. MSP is using 115200 and MAVLink 57600 baud. By looking at the OcuSync Air Unit Telemetry Tx line, I see that it is using 115200 baud MSP and 57600 baud MAVLink after cold start back-to-back to query with which protocol it should talk to the connected flight controller/OSD.
My fault was that I was using 115200 setting in ArduPilot SERIALx_BAUD, also for MAVLink, whereas for MAVLink ArduPilot baud rate needs to be set to 57600 baud (also for the debug-tool… which was an error in my part).
For someone interested in more nitty-gritty detail can read on down below, for someone just to have a brief overview, here’s a quick summary: DJI Goggles RE with OcuSync Air Unit will also output telemetry to ArduPilot with SERIALx_PROTOCOL set to 1 (MAVLink1), it is important that the SERIALx_BAUD is set to 57. With MAVLink you although do not get GPS data (no coordinates, no satellite count) displayed in Goggles RE, whereas with MSP you do.
Here now in detail. What the DJI OcuSync Air Unit is doing on power-up is:
Step 1. OcuSync Air Unit requests using MultiWii Serial Protocol (MSP) at 115200 six values, namely:
1.1) 0x24 0x4D 0x3C 0x00 0x65 0x65, which is MultiWii request for message type 101 “GET MSP_STATUS”.
(0x24 = “$”, 0x4D = “M”, both together are the MSP preamble “$M”, 0x3C is direction and “<” means request, payload length is 0 and message type is 0x65=101=MSP_STATUS, last 0x65 is XOR checksum, which by zero payload length is always the same byte as the message type)
1.2) 0x24 0x4D 0x3C 0x00 0x6A 0x6A, which is MSP Request 106 = GET MSP_RAW_GPS
1.3) 0x24 0x4D 0x3C 0x00 0x6B 0x6B = MSP Request 107 = GET MSP_COMP_GPS
1.4) 0x24 0x4D 0x3C 0x00 0x6C 0x6C = MSP Request 108 = GET MSP_ATTITUDE
1.5) 0x24 0x4D 0x3C 0x00 0x6D 0x6D = MSP Request 109 = GET MSP_ALTITUDE
1.6) 0x24 0x4D 0x3C 0x00 0x6E 0x6E = MSP Request 110 = GET MSP_BAT
And now happens the trick that I was previously not able to decode, as I had my debug tool at 115200 baud - OcuSync switches to 57600 baud and sends out MAVLink v1 frame:
Step 2. 0xFE 0x06 0x00 0x01 0x01 0x42 0x64 0x00 0x01 0x01 0x00 0x01 0xD1 0x80
Here’s the byte-by-byte decoding of the MAVLink v1 telegram:
0xFE MAVLink v1 packet start
0x06 payload size = 6 bytes
0x00 packet sequence 0
0x01 System ID = 1
0x01 Component ID 1
0x42 Message ID 0x42 = 66 = REQUEST_DATA_STREAM
Next 6 bytes are payload 64 00 01 01 00 01 and they mean target system 0x64 = 100, target component = 0, req_stream_id = 1, req_message_rate (uint16) = 1 Hz, 1 start sending
0xD1 low byte of CRC-16 checksum
0x80 high byte of CRC-16 checksum
Step 3. then OcuSync Air Unit switches back to 115200 baud and requests again the 6 values using MSP as in step 1 above.
Step 4. it changes again back to 57600 baud and requests again the same stream start, but now with packet sequence being 1 and a new CRC because of changed content naturally.
After this, OcuSync Air unit stops streaming out (in my case with MatekF405-CTR), as the MAVLink messages from flight controller start coming in. In Goggles RE, I can see orientation, height, speed, battery voltage and current, but no GPS data. GPS presently only works in MSP mode.
In comparison, with flight controller in MSP mode, OcuSync Air Unit keeps repeatedly polling the 6 MSP requests, as in step 1 above (at roughly 100 Hz).
Update: for someone interested, I add two Saleae Logic analyzer software captures of DJI OcuSync Air Unit telemetry Rx and Tx lines during the first 10 seconds after cold start:
Saleae capture of OcuSync Air Unit with ArduPilot in MAVLink1 mode.zip (142.0 KB)
Saleae capture of OcuSync Air Unit with ArduPilot in MSP mode.zip (997.3 KB)