UPixels T101-Plus/T201 Optical Flow¶
UP-T101-Plus and UP-T201 are an optical flow + laser 2-in-1 module, mainly used in drones to achieve both horizontal and vertical positioning functions, more suitable for indoor use.
Where to Buy¶
The sensor is available from various retailers. Here are some links:
For those in China:
Connection to Autopilot¶
UP-T101-Plus Wiring Diagram:¶

UP-T201 Wiring Diagram:¶

The flow sensor should be mounted on the underside of the copter with the camera lens pointing downwards.
Connect the sensor’s GND and TX pin to one of the autopilot’s serial ports. Note that the TX pin of the sensor should be connected to the RX pin of the autopilot. In the image above the sensor is connected to the Telem2 port.
Connect the sensor’s VCC to a 3.3V or 5V power source.
Configuration and Parameters¶
Set FLOW_TYPE = 9
Set MAV2_EXTRA3 = 50 (assuming that Telem1 is also MAVLink protocol)
Set SERIAL2_BAUD = 115200
Set SERIAL2_PROTOCOL = 16
Set RNGFND1_TYPE = 45
Set RNGFND1_ORIENT = 45
Set RNGFND1_MAX = 4 (The UP-T101-Plus is set to 4 and the UP-T201 is set to 15)
Set RNGFND1_MIN = 0.02 (The UP-T101-Plus is set to 0.02 and the UP-T201 is set to 0.05)
Once the sensor is activated, you should be able to observe the optical flow and distance sensor data on the Status page of the task planner. “opt_m_x”, “opt_m_y”, “opt_qua” and “rangefinder1” data have been updated.
Additional Notes¶
As with the PX4Flow sensor a range finder is required to use the sensor for autonomous modes including Loiter and RTL
Performance can be improved by setting the sensors position parameters. For example if the sensor is mounted 2cm forward and 5cm below the frame’s center of rotation set FLOW_POS_X to 0.02 and FLOW_POS_Z to 0.05.
Testing and Setup¶
See Optical Flow Sensor Testing and Setup for setup guides.
Details of the modules are available: UPixels_GitHub.
Note that recommended value for EK2_FLOW_DELAY or EK3_FLOW_DELAY for this sensor is 10.