Failsafe Triggered: "Invalid Setpoints" and Blind Land with Here4 GPS

Hello all,

I’m currently working on a custom aircraft setup running PX4 firmware v1.15.0. The system includes:

  • Flight Controller: CubePilot CubeBlue

  • GPS: Here4 (connected via the blue UAVCAN cable to the CAN2 port on a KORE carrier board)

  • Firmware: PX4 v1.15.0

I’m encountering a persistent issue during flight testing. At some point during each flight (only once per flight), I receive the following messages:

[Warning]: Invalid Setpoints.  
[Warning]: Failsafe: blind land

This occurs regardless of whether the aircraft is armed or not. The Here4 GPS appears to function normally otherwise, and this issue is consistent across multiple flights.

Troubleshooting Attempts

To mitigate the issue, I initially tried increasing the parameter EKF2_NOAID_TOUT from the default 5 seconds to 7 seconds. This change resulted in intermittent triggering of the “blind land” failsafe.

Pushing the timeout further to 10 seconds helped reduce the frequency of the blind land, but introduced toilet bowling behavior during hover, which seems to indicate degraded EKF performance or poor heading estimation.

Has anyone encountered similar behavior—especially the exact timing of the failsafe around 250s? I’m particularly interested in:

  • Relevant parameters to tune or monitor

  • UAVCAN diagnostics or logging advice

  • Interactions between EKF2, GPS, and failsafe logic that might explain this pattern.

PS: This issue in not seen in v1.14.x

Thanks in advance!

Further debugging:

The Problem

Multicopters were experiencing a critical “Failsafe: blind land” event consistently around 256-260 seconds during flight. This was not a GPS signal quality issue, but rather a systematic 5-6 second window where GPS fusion would completely stop, leading to EKF2 entering inertial dead reckoning mode and triggering the failsafe.

Initial Investigation

The investigation began by tracing the failsafe trigger back through the system:

  1. mc_pos_control was generating “invalid setpoints” and triggering “Failsafe: blind land”

  2. This occurred when states.velocity.xy became invalid due to EKF2 losing horizontal position validity

  3. EKF2 was entering inertial dead reckoning mode, causing xy_valid to drop to false

Root Cause Discovery

Through extensive logging and analysis, we discovered the real issue was upstream in EKF2’s GPS fusion logic:

The 1-Second Timeout Bug (Fixed First)

  • EKF2 was using a hardcoded 1-second no-aid timeout instead of respecting the EKF2_NOAID_TOUT parameter

  • Fixed by making no_aid_timeout_max mutable and updating it from the parameter

The GPS Sample Dropping Issue (Main Problem)

  • GPS data was continuously arriving and being buffered (confirmed via logs)

  • GPS fusion was working perfectly when attempted (confirmed via logs)

  • The issue was that EKF2 was dropping GPS samples when runGnssChecks() failed, even during active GPS fusion

  • This created 5-6 second windows where no fusion occurred, triggering the no-aid timeout

Debugging Process

  1. Added comprehensive logging to track:

    1. GPS data readiness and buffer state
    2. Fusion attempt timing and success/failure
    3. Control flags and gating conditions
    4. Dead reckoning transitions with timing deltas
  2. Key findings from logs:

    1. GPS data continued arriving every ~10ms with push_age=0.000s
    2. No “GPS data NOT ready” or buffer pop failures during the critical window
    3. No fusion attempts occurred for ~5 seconds despite fresh data being available
    4. The issue was in the sample-level GPS checks logic, not data availability
  3. Identified the exact code path: cpp

    1. if (runGnssChecks(gnss_sample) && isTimedOut(_last_gps_fail_us, ...)) {
             // Process sample
         } else {
             // Skip this sample - THIS WAS THE PROBLEM
             _gps_data_ready = false;
         }
      

The problem was that when GPS checks failed (due to momentary quality dips), the code would set _gps_data_ready = false, dropping the sample entirely. This happened even when GPS fusion was already active and working. The dropped samples created starvation periods leading to the 5-second no-aid timeout.For now my solution:Modified the GPS sample dropping logic in src/modules/ekf2/EKF/gps_control.cpp

else {
    // Checks not passing for this sample. If GPS fusion is already active and samples are recent,
    // continue to process the data to avoid creating long no-aid gaps leading to DR.
    // Only drop the sample if GPS aiding is not active yet.
    if (!_control_status.flags.gps) {
        _gps_data_ready = false;
    }
}

How It Works

  • Before: Any GPS sample that failed checks was dropped, regardless of fusion state

  • After: Only drop samples if GPS fusion is not yet active (!_control_status.flags.gps)

Result: During active GPS fusion, samples continue to be processed even if checks fail momentarily

I am not sure of the solution though. Since the code base is huge. I would like to know what problems could arise because of this implementation.

Thank you in advance!