Cheerson CX-OF Optical Flow

The Cheerson CX-OF optical flow sensor is a lightweight and low cost optical flow sensor which can be used to improve horizontal position control especially in GPS denied environments.

Where to Buy

The sensor is available from various retailers incluing Banggood.com and AliExpress. More retailers can be found by searching for “CX-OF spare parts”.

These alternatives have also been shown to work:

These alternatives may work but this has not been confirmed:

Connection to Autopilot

../_images/cheerson-cxof-pixhawk.jpg
  • The flow sensor should be mounted on the underside of the copter with the camera lens pointing downwards. The side of the sensor with the “V2.0” label should be towards the front of the vehicle. The image above is incorrect because the autopilot’s arrow is pointing down while the sensor’s “V2.0” label is close to the top.

  • Connect the sensor’s TX and VSS (aka GND) pins to one of the autopilot’s serial ports. In the image above the sensor is connected to a Pixhawk’s Telem2 port

  • Connect the sensor’s VDD (aka VCC or 3.3V) to a 3.3V power source. In the above diagram the Pixhawk’s Switch port is used but another alternative would be the SPKT/DSM port’s power pin

  • Set FLOW_TYPE = 4

  • Set SERIAL2_PROTOCOL = 18 if using Serial2/Telem2, if connected to another serial port use the corresponding SERIALx_PROTOCOL parameter

Additional Notes

  • As with the PX4Flow sensor a range finder is required to use the sensor for autonomous modes including Loiter and RTL

  • FlowHold does not require the use of a rangefinder

  • The sensor has been successfully tested to altitudes of about 40m

  • 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