* fix(navigator): guard terrain altitude check for position mission items
updateAltToAvoidTerrainCollisionAndRepublishTriplet() calls
get_absolute_altitude_for_item() on the current mission item without first
checking whether the item contains a position.
For non-position mission items, the altitude field has no setpoint meaning.
Using it in the terrain descent condition can make the check operate on an
invalid mission-item altitude.
Add the same item_contains_position() guard used by other mission altitude
handling paths before reading the mission item altitude.
* navigator: remove redundant mission item checks
Remove checks already covered by item_contains_position() and update the
terrain avoidance comment to match the current condition.
* SITL: mavlink bind to a specific interface using an environment variable PX4_NET_INTERFACE
Fixes issue #26384
* document the usage of PX4_NET_INTERFACE
* Improved Docs:
- Added new Environment Configuration subsection at the end of SITL Simulation
- Removed the old Bind MAVLink to Specific Network Interface subsection (content consolidated into the new section)
---------
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
* EKF2: guard EV position bias updates on active fusion
Horizontal position resets were updating the external vision position bias
estimator even when EV position fusion was not active.
This is the same bug pattern as #27094. In resetAltitudeTo(), the height bias
estimators are only shifted when the corresponding height source is currently
being fused, for example _ev_hgt_b_est is updated only when
_control_status.flags.ev_hgt is true. That guard prevents an inactive EV height
bias estimator from being modified by an EKF state reset.
The horizontal reset paths did not have the equivalent guard. Both
resetHorizontalPositionTo() and resetLatLonTo() unconditionally applied
delta_horz_pos to _ev_pos_b_est. However, controlEvPosFusion() treats
_control_status.flags.ev_pos as the active EV position fusion state, and the
position observation is later computed as:
measurement - _ev_pos_b_est.getBias()
This means a horizontal position reset from another source could shift the EV
position bias estimator while EV position fusion was inactive. When EV position
fusion later resumed, the stale shifted bias could be used in the EV observation
path and produce incorrect innovations.
Only update _ev_pos_b_est during horizontal resets when EV position fusion is
currently active, matching the guarded resetAltitudeTo() behavior fixed by
* Update src/modules/ekf2/EKF/position_fusion.cpp
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
---------
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
AirspeedSource::SYNTHETIC is declared after SENSOR_3, so its integer value is
4 while _airspeed_validator only has MAX_NUM_AIRSPEED_SENSORS entries, with
valid indices 0..2.
select_airspeed_and_publish() only checked whether _prev_airspeed_src was less
than SENSOR_1 before indexing:
_airspeed_validator[prev_airspeed_index - 1]
When _prev_airspeed_src is SYNTHETIC, prev_airspeed_index is 4 and this becomes
_airspeed_validator[3], which is out of bounds. Treat sources above SENSOR_3 as
non-sensor sources so only SENSOR_1..SENSOR_3 can index the validator array.
This fixes the same class of bug as #27232. The external position
reset-by-fusion path explicitly intends to strongly correct correlated
states, including heading, as documented by the existing comment next to
the artificial Kalman gain increase.
However, when VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE is handled in
EKF2::Run(), it runs before _ekf.update(), so heading_observable can
still reflect the previous controlFusionModes() result. If it is false,
clearInhibitedStateKalmanGains() inhibits the intended heading
correction.
Set heading_observable before the external position fusion so the reset
can preserve the documented correction of correlated states. The normal
EKF update path recomputes the flag afterwards.
* fix(ekf2,commander): split "no heading source" from heading-innovation-failure
The pre_flt_fail_innov_heading flag conflated two distinct conditions: bad
heading innovations and the absence of any heading source. Optical-flow-only
quad setups (no magnetometer, no GNSS yaw, no external-vision yaw) never set
yaw_align, so the flag latched true and produced a misleading
"Preflight Fail: heading estimate invalid" message in modes that don't
actually depend on heading.
EKF2: pre_flt_fail_innov_heading now reports innovation failures only.
Commander: a new branch consumes estimator_status_flags.cs_yaw_align (when
fresh) to block heading-required modes (POSCTL, AUTO_*, ORBIT, AUTO_LAND,
FW AUTO_TAKEOFF) when no source is present, with a new "no heading
reference" message. The branch only fires for fresh estimator_status_flags
data so external-INS drivers (MicroStrain, VectorNav, ILabs, sbgecom) that
don't publish the flags topic retain prior behaviour. PR #26778's
mode-scoping and PR #26596's silent-pass protection are both preserved.
Resolves#27107.
* style: trim source comments per review
* Apply suggestions from code review
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
* refactor(commander): move no-heading-source check into checkEstimatorStatusFlags
* Update src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
---------
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>