Cheerson CX-OF low cost optical flow sensor testing

Hello everybody ,
I don’t know if this is the right place , i’d like to share my idea and to know if have some chance of success or viceversa i’m wasting my time

I have an OpenMV Cam and recently i modified the script called “mavlink_opticalFlow.py” to send the information in the same way as Cheerson CX-OF serial protocol
immagine

I followed the instruction to use the CX-OF sensor
http://ardupilot.org/copter/docs/common-cheerson-cxof.html

I forced to use uart in SITL

immagine

And I received the data from OpenMVCam


Something like this…
immagine

First question:
How is calculated the CXOF_PIXEL_SCALING ?
It’s possible to use the FLOW_F…SCALER instead of CXOF_PIXEL_SCALING ?

As result of first real test with my quadcopter I logged these data. The copter was in oscillation in roll and pitch axis. FlowX vs BodyX is uncorrelated but viceversa FlowY vs BodyY is correlated

Could be only a problem of orientation ?

The data from flow sensor are not linear ( i didn’t set EK2_FLOW_DELAY ) or scale problem ?


Any comments will be appreciated
Thank

1 Like

That is interesting :slight_smile:

You might have camera orientation issue indeed, you deed to do a roll and pitch test as described in the PX4FLOW wiki.

have you looked at my calibration result above ?

very interesting. i didn’t realise someone had written a script to allow the OpenMV camera to be used as an optical flow sensor. I guess you’re modifying the script because we don’t have a driver to directly accept the mavlink messages? A few people have asked for such a driver so we really should write that…

Thank you for your answer , you inspired me with your work with OpenMV!

Yes i read the article but probably I didn’t follow the right procedure
I supposing the output of the flow when moving must be as follows

Forward +Y
Backwards -Y
Right -X
Left +X

At the begin I tried to check the direction reading the data from the terminal console on OpenMV IDE.
But It’s not easy , the best thing would be to log the data and print a graph .
After the test with SITL ( only for serial driver ) the next step was to tuning the flow data with mission planner

I was convinced to read the flow data on the Flight Data screen’s Status tab before to flight , but these values was always zero. I think that may be the best method to check the signal trend.

After that I decided to test on flight, just in hovering to get enough data to log.

Anyway I will try to repeat the previous steps to get the flow values and gyro values with the same trend
About the amplitude if I understand I may adjust the values analyzing the signals trace

1 Like

Yes exactly! , I bought the OpenMV and I discovered an example for Mavlink Optical Flow.

But in the example the data has been sent with the mavlink message and like you said , there is not driver for that

I don’t have the knowledge to understand if the optical flow in MV cam can be used for this scope but I thinked if work the PMW3901 optical sensor why not try with this powerful camera ?

I had an optical lens of 16mm so i mounted, wrote the python function and tested…
But i have some doubt about the "pixel scaling" and the quality of the flow

Now become a little complicate the analysis :smile:

1 Like

Is this optical flow included in 3.7.0 dev for omnibus nano v6?
I’m testing it but “bad optical flow health” message appears.
I’ve connected CX-OF on TLM port and configured serial1 (tried serial2 instead with same results)

Regards,
Meme

Maybe @rmackay9 can confirm, but I don see any PR related to the patch for univerasl usage of optical flow on all platforms.
Have you considered to appy the patch ? It is not really hard as it is just adding a line in the code and build using waf for the omnibus nano

Look here

1 Like

I hope to get a PR in master some time soon-ish to support the cx-of on all platforms… txs for the help and interest!

1 Like

Thanks to all for your interesting
I’ll try as per ppoirier, but probably Randy will be faster than me…

Regards,
Meme

I’ve created a PR to add support for the CX-OF to all boards and also put an omnibus-nano-v6 binary here.

@ZioMeme, I was wondering if you’d be willing to try this on your board to see if you can get the cx-of working? Please becareful because this is based on Copter-3.7.0-dev so it hasn’t gone through beta testing.

I’m happy to make a test binary for anyone else who would like to help me confirm the change is working for other boards (I’ve already tested the change does not break anything on a Pixhawk1 board)

1 Like

@DomenicoPatella,

I’ve started working on an optical flow driver that accepts the MAVLink OPTICAL_FLOW messages. The branch is here.

There’s probably a bug or two but it might work.

EDIT: I thought the OpenMV script was sending data in the flow_comp_m_x/flow_comp_m_y fields but after a short test I see it is correctly sending in the flow_x and flow_y fields.

EDIT2: I’ve also figured out how to connect the OpenMV to my flight controller’s Telem1 port. It basically seems to work although I haven’t really tested it much yet.

1 Like

Does anybody have a link to order a cx-of? Because both links in the documentation are sold out…

Thanks

Thanks Randy,
it’ll be my pleasure to update you on testing on this board

1 Like

Not a supplier I’ve ever used, but https://www.rc-helicopter-spare-parts-online.com/cheerson-cxof-rc-quadcopter-spare-parts-optical-flow-module-p-15935.html

Great job Randy ! in my test i connected the Open MV camera on Telemetry port 2
Tx (P4) >> Rx
+5V <<. +5V
GND << GND
With the original script loaded on OpenMv i read the message #100 OPTICAL_FLOW with mavlink inspector (QCG) flow_x/ flow_y

I’d like to do some test in fly . Hope to update you as soon as possible

The power consumption reported from manufacturer is max 200mA at 3.3V(M7) 140mA at 3.3V (H7)
https://openmv.io/collections/products/products/openmv-cam-h7
https://openmv.io/collections/products/products/openmv-cam-m7

Hey Randy, I am applying for GSoC this year . In the problem statement https://github.com/ArduPilot/ardupilot/pull/10539 its there to create an easy to use optical flow sensor calibration method. I thought about getting the optical flow sensor messages over mavlink and pass it to an auto-tuner which it will be used to decrease the error (OF.flowX - Of.bodyX) by changing the FLOW_SCALAR parameter until the error reduced to its minimum.
But i think half of the work is already done!

Hi Piyush,

For the optical flow calibration routine, I don’t think that PR from Paul adds the automatic calibration so the enhancement request is still a good one to pursue.

Yes, it’s the FLOW_SCALAR parameters that need to be adjusted to reduce the error between the sensor and gyros. We have a few different drivers to get optical flow data into AP including Serial (for the cx-of), I2C (for the px4flow sensor) and SPI (for the Pixart sensor that’s on the SkyViper drones) but it shouldn’t matter which driver is used from the calibration algorithm’s point of view. This new algorithm should work with the data from the sensor regardless of which protocol has been used.

Looking forward to seeing the GSoC proposal!

Might have a substitute available at bangood
https://usa-m.banggood.com/JJRC-H62-RC-Quadcopter-Spare-Parts-Optical-Current-Board-H62-03-p-1302982.html

1 Like

@ppoirier, txs for the link. I’ll try and remember to add it to the wiki with the other potential substitute we’ve found. I might buy them both to test if they work but if anyone else discovered whether they work or not please update us. :slight_smile:

@ppoirier if I remember correctly you have also this one:


Have you ever tested it to see which protocol is used?