Closed mike239x closed 4 years ago
Welp I gained some knowledge so I will try to answer my own questions.
distance_valid = true;
and comment out https://github.com/PX4/Flow/blob/master/src/modules/flow/main.c#L417, and you are done, now you can get speed in m/s from OPTICAL_FLOW messages. One can also take the code that actually sends the message - https://github.com/PX4/Flow/blob/master/src/modules/flow/main.c#L605 - and backtrack how the variables involved are computed.@mike239x Thanks for answering your own questions, I had many of the same. Can you point me to the discussion/information that answered your question 2? I'm working with low-light environments and found that the received data doesn't slow down until exposure time is >1000. I want to increase it further, so I'm looking for some guidelines on what might be an acceptable update rate.
@RickReeser For me that was mostly experimenting + reading source code. I compared old/new versions of code for flow computation, and saw that only a few minor bugs were changed. Then I found how to change exposure in either version, and saw that new code behaves quite the same as the old one if you lower exposure and vice versa.
Regarding your question, I don't know how "low-light" is it in your case, in my case even with exposure of 100 one can see things on the video-feed, and generally the lower exposure you got, the better.
Assuming you actually do want to get exposure above 1000 - I don't know how well your camera is suited for that and how blurry the images would be, but whatever - I imagine that in your case the flow computation gets slow. One easy way to check that is to take a look at the debug images and see if all debug dots are lit - like so:
If that is the case one easy way to fix things is to try to adjust BFLOW_F_THLD
parameter by making it somewhat higher.
Another few things you can adjust to increase speed of optical flow computation is to change BFLOW_MAX_PIX
to 4 and to change NUM_BLOCKS
in line 55 of flow.c
to 4 or 3 + comment out line 522.
If however that does not help I am not sure I can help you - you would have to add debug output + timing to the code, benchmark everything to find what is causing your problems.
@mike239x ah okay, in that case thanks for doing some of the research for me.
I was able to turn exposure up to 2000us (>2000 caused some kind of oscillation). I was "measuring" update rate by just looking at the frequency of received MAVLink ENCAPSULATED_DATA packets, which seemed to max out at ~350 Hz and started decreasing if I increased exposure more than 1000. At 2000us exposure, updates were still >200 Hz which seemed acceptable to me, so I wasn't sure if my measuring method was valid. I had the feature threshold at 5 to force it to use the whole frame.
The increased exposure definitely makes the flow measurements less noisy in a static scene, and 230Hz update is good enough, I reckon. If that's a valid way to measure update rate, then I guess I just need to determine if the extra blurriness is acceptable.
On a side note, with the 2014 firmware that ships with the PX4Flow, the update rate was only ~120Hz, even with low light mode off.
Welp, this is confusing. First, a few things I am certain about: 1) If you desire so, you can still speed opt.flow computation as described above. 2) If I understand it correctly, the camera collects photons till exposure time is up OR the desired brightness is achieved. Also, it seems the camera can't capture faster than 400Hz. That mostly explains the rate behavior you observe. What confuses me is this: 1) It is quite unclear to me what firmware version you use and what settings you have there. 2) Maybe as part of the first point, I find it weird to have 2000us exposure time unless it is really dark, so mb reference to what firmware you have + what your settings are would be good.
Good day,
I got myself a px4flow camera which I want to use for purposes that it isn't really tailored to do. I wanted to ask quite a few questions about documentation / firmware / data processing.
AEC
andAGC
.klt
inside them, for example theklt
branch " is 149 commits ahead, 35 commits behind master". I also can get ArduPilot firmware from QGroundControl. And last but not the least, I saw user vmanoj1996 make the following claim in his fork of this repo: "The master branch of PX4/Flow seems to compute optical flow at lesser rate than the advertised 400Hz (its somewhere around 50Hz). This problem limits the maximum optical flow (and by extension, the maximum speed measurable) below usable levels. The default firmware shipped with px4flow sensor is based on a 2014 commit." This seems to be true from my experiments, but since I do weird stuff like testing the sensor indoors fairly close to the ground I wanted to get a comment on whether that is true.flow_comp_m_x
,flow_comp_m_y
andground_distance
are all zeros. I saw people just hack the code to make it look like sonar is always measuring the same depth in order to fix this issue, so I was wondering if that is the best way to do things. Another option for me would be to process the raw data I get locally, but I do not know how to convert that raw data into meters (m/s?).settings.c
I see onlyEXPOSURE_MAX
, which I assume is not the right thing? It also isn't documented so I don't really know.