Optical flow never fuses when no GPS

Hardware: MicoAir H743-V2 + MTF-02P (optical flow + rangefinder combined sensor)
PX4 version: v1.17.0-beta1

I’ve been trying to get optical flow working without GPS using the MTF-02P sensor. Despite the sensor working correctly, cs_opt_flow was never becoming true and dist_bottom_valid was always false in the local position estimate.

After extensive debugging I found a circular deadlock in the EKF2 code when using this configuration:

  • EKF2_HGT_REF = 2 (Range)

  • EKF2_RNG_CTRL = 2 (Enabled)

  • EKF2_GPS_CTRL = 0 (no GPS)

Root cause: starting_conditions_passing in optical_flow_control.cpp requires isTerrainEstimateValid() || isHorizontalAidingActive(). With no GPS, isHorizontalAidingActive() is false. And isTerrainEstimateValid() can never become true because:

  • rng_terrain is disabled when range is the height reference

  • opt_flow_terrain needs optical flow to be running first

So optical flow needs terrain, terrain needs optical flow — a deadlock with no way out.

Fix: Add || (_height_sensor_ref == HeightSensor::RANGE) to starting_conditions_passing. When range is the height reference, the system already knows the distance to ground — no separate terrain estimate is needed to safely start optical flow fusion.

Has anyone else hit this? Is this the right fix or is there a better approach?

I have found similar post

Fixed in fix(ekf2): allow optical flow to start when range finder is height reference by dakejahl · Pull Request #26960 · PX4/PX4-Autopilot · GitHub

This topic was automatically closed 7 days after the last reply. New replies are no longer allowed.