docs(optical_flow): clarify that integrated flow values are angular, not translational (#26811)

The flow output table shows forward movement producing +Y flow and
rightward movement producing -X flow, which confuses users whose sensors
have X-forward/Y-right coordinate systems. Add an info note explaining
that integrated flow values are angular rotations (radians) about the
body axes using the right-hand convention, which is why the axes are
cross-coupled with translational motion.
This commit is contained in:
Jacob Dahl 2026-03-18 14:53:16 -08:00 committed by GitHub
parent 547eb77a55
commit 6ee825f485
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194

View File

@ -34,6 +34,12 @@ The output of the flow when moving in different directions must be as follows:
| Right | - X |
| Left | + X |
::: info
The integrated flow values are **angular measurements** (radians) representing rotation of the image about the sensor's body axes using the right-hand convention.
They are _not_ translational displacements along those axes, which is why forward vehicle movement (along X) appears in the Y flow axis, and rightward movement (along Y) appears in the X flow axis.
Specifically, forward movement causes the ground image to rotate about the Y axis (+ Y), while rightward movement causes a negative rotation about the X axis (- X).
:::
Sensor data from the optical flow device is fused with other velocity data sources.
The approach used for fusing sensor data and any offsets from the center of the vehicle must be configured in the [estimator](#estimators).