Decoding The 3901-L0X Optical Flow TX Data

I need help to decode the raw delta-x and delta-y data from the TX/RX serial pins on the Optical Flow Lidar Sensor SKU: 3901-L0X. What do each of these bytes represent?

Baud rate: 115200
Byte size: 32

Sample of Output:
5C 3E 0 0 1F 41 FFFFFFFF 2B 0 0 2 24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC4 24 58 3C 0 1 1F 24
5C 3C 0 1 1F 5 0 69 40 0 FFFFFFFA 24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC5 24 58 3C 0 1 1F 0
0 24 58 3C 0 1 1F 5 0 FFFFFFFF 63 1 0 0 FFFFFF92 24 58 3C 0 1 1F 5 0 FFFFFFFF 6C 1 0 0 FFFFFFCB 24 58 24
58 3C 0 1 1F 5 0 FFFFFFFF 70 1 0 0 FFFFFFF3 24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC5 24 58 3C 0 24
58 3C 0 1 1F 5 0 FFFFFFFF 6D 1 0 0 FFFFFF8E 24 58 3C 0 1 1F 5 0 FFFFFFFF 65 1 0 0 FFFFFFD9 24 58 3C 0 24
58 3C 0 1 1F 5 0 FFFFFFFF 72 1 0 0 79 24 58 3C 0 1 1F 5 0 FFFFFFFF 68 1 0 0 A 24 58 3C 0 24
58 3C 0 1 1F 5 0 FFFFFFFF 72 1 0 0 79 24 58 3C 0 1 1F 4 0 FFFFFFFF 60 1 0 0 5D 24 58 3C 0 24

#include <SoftwareSerial.h>

SoftwareSerial flowSerial = SoftwareSerial(2,3);

char msg[256];

void setup() {
  // put your setup code here, to run once:
  Serial.begin(115200);
  flowSerial.begin(115200);
Serial.setTimeout(10);

}

void loop() {
  // put your main code here, to run repeatedly:
  int n;

  if( flowSerial.available()){
        flowSerial.readBytes(msg,32);
 

for( n = 0; n < 32; n++){
//  z = (int)(word(msg[n + 1], msg[n]));
  Serial.print(msg[n],HEX);
  Serial.print(" ");
}
Serial.println();
}

delay(1000);
}

Sorry about the links and descriptions, I have re-checked your binary hex output.

I have did some study about ArduPilot开源飞控之AP_OpticalFlow

If you are using MatekSys Optical Flow 3901-L0X, then you need to configure SERIALx_PROTOCL=32. It’s MSP by default, and which is confirmend from you binary hex log SOF=0x24, V2=0x58.

BTW, there are different kind of protocol for optical flow, so I have made a mistake previously. Check here for details.

You should start by formatting the output (which looks like an input) correctly:

24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC4
24 58 3C 0 1 1F 24 5C 3C 0 1 1F 5 0 69 40 0 FFFFFFFA
24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC5
24 58 3C 0 1 1F 00
24 58 3C 0 1 1F 5 0 FFFFFFFF 63 1 0 0 FFFFFF92
24 58 3C 0 1 1F 5 0 FFFFFFFF 6C 1 0 0 FFFFFFCB
24 58
24 58 3C 0 1 1F 5 0 FFFFFFFF 70 1 0 0 FFFFFFF3
24 58 3C 0 1 1F 5 0 FFFFFFFF 6B 1 0 0 FFFFFFC5
24 58 3C 0
24 58 3C 0 1 1F 5 0 FFFFFFFF 6D 1 0 0 FFFFFF8E
24 58 3C 0 1 1F 5 0 FFFFFFFF 65 1 0 0 FFFFFFD9
24 58 3C 0
24 58 3C 0 1 1F 5 0 FFFFFFFF 72 1 0 0 79
24 58 3C 0 1 1F 5 0 FFFFFFFF 68 1 0 0 A
24 58 3C 0
24 58 3C 0 1 1F 5 0 FFFFFFFF 72 1 0 0 79
24 58 3C 0 1 1F 4 0 FFFFFFFF 60 1 0 0 5D
1 Like

Here’s a start, MSP must be one of the worst documented protocols in history…:

Header | Direction  | Flag | Function | Payload Length | 0 | Payload           | CRC
24  58 | 3C         | 0    | 1 1F     | 5              | 0 | FFFFFFFF 6B 1 0 0 | FFFFFFC4
 $   X | <          | 0    | 287      | 5              | 0 | FFFFFFFF 6B 1 0 0 | FFFFFFC4
MSP V2 | FC->Sensor | 0    | you'll need to look through the code for function and payload