Skip to content

thebandofficial/position-injection-examples

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

2 Commits
 
 
 
 
 
 
 
 

Repository files navigation

PX4 v1.14 position injection examples

this repo has python and c++ examples of usage of mavlink messages:

  • GPS_INPUT (ID 232),
  • VISION_POSITION_ESTIMATE (ID 102), and
  • GLOBAL_VISION_POSITION_ESTIMATE (ID 101)

In the examples, make sure to use your own connection string. the default hard-coded one is: "serial:///dev/ttyTHS0:921600"

PX4 v1.14 — Extended Kalman Filter 2 (EKF2) parameters that make MAVLink GPS/Vision affect vehicle position

This guide covers the EKF2 parameters in PX4 v1.14 .params file (see examples in this repo) that control whether data from:

  • GPS_INPUT (ID 232),
  • VISION_POSITION_ESTIMATE (ID 102), and
  • GLOBAL_VISION_POSITION_ESTIMATE (ID 101)

is accepted and fused into the vehicle’s navigation solution.

EKF2 parameter docs(v1.14): PX4 v1.14 Parameter Reference – EKF2 section

🛈 In v1.14, legacy parameters were replaced:

  • Old EKF2_AID_MASK ➜ replaced by per-source control params (e.g., EKF2_GPS_CTRL, EKF2_EV_CTRL, EKF2_OF_CTRL, …).
  • Old EKF2_HGT_MODEEKF2_HGT_REF (selects the height reference).

1) Turn fusing on for each source (v1.14 controls)

These parameters are the “master switches” in 1.14:

EKF2_GPS_CTRL — GNSS/GPS fusion control

Enables the kinds of GPS measurements to fuse (pos/vel/heading). Also used when your GPS data arrives via GPS_INPUT (232). Docs and examples explicitly reference this param for yaw/dual-antenna setups.

EKF2_EV_CTRL — External Vision fusion control

Select which vision signals to fuse (horizontal position, vertical position, 3D velocity, yaw, etc.). This is the v1.14 replacement for setting vision bits in EKF2_AID_MASK.

If you’re feeding VISION_POSITION_ESTIMATE (102) or GLOBAL_VISION_POSITION_ESTIMATE (101), make sure the corresponding bits in EKF2_EV_CTRL are enabled.


2) Pick the height reference

EKF2_HGT_REF — Height reference selector

Chooses the long-term height reference: Baro / GPS / Range / Vision.
This replaces the older EKF2_HGT_MODE. External vision height only takes effect if HGT_REF = Vision.


3) Vision (VIO/MoCap) parameters that affect fusion of 101/102

When streaming VISION_POSITION_ESTIMATE (102) or GLOBAL_VISION_POSITION_ESTIMATE (101):

  • EKF2_EV_CTRL — enable desired fusions (pos/vel/yaw).
  • EKF2_EV_DELAY — compensate camera/VIO pipeline latency (s).
  • Vision noise/uncertainty (how much EKF trusts vision):
    • EKF2_EVP_NOISE — position noise
    • EKF2_EVV_NOISE — velocity noise
    • EKF2_EVA_NOISE — attitude (yaw/roll/pitch) noise
    • EKF2_EV_NOISE_MD — choose whether EKF uses these params or the covariance coming in via MAVLink (e.g., ODOMETRY).
  • Sensor placement offsets:
    • EKF2_EV_POS_X, EKF2_EV_POS_Y, EKF2_EV_POS_Z — camera/vision sensor position relative to the IMU (m). (Listed under EKF2 external vision setup in v1.14 docs.)

Notes
• PX4 fuses vision in its estimator frame; global vision (101) is internally transformed to the local EKF frame once the origin is known.
• If you want vision altitude to influence Z, set EKF2_HGT_REF = Vision.


4) GPS parameters that gate/shape fusion of GPS_INPUT (232)

  • Enable GPS fusion: EKF2_GPS_CTRL (select pos/vel/yaw/dual-antenna heading options).
  • Quality gates (must pass before fusion):
    • EKF2_GPS_CHECK + the EKF2_REQ_* family (e.g., EKF2_REQ_EPH, EKF2_REQ_EPV, EKF2_REQ_PDOP, EKF2_REQ_NSATS, EKF2_REQ_VDRIFT, EKF2_REQ_HDRIFT, EKF2_REQ_SACC). These are widely used thresholds in v1.14 setups.
  • Timing/latency: EKF2_GPS_DELAY — align GPS with IMU time.
  • Antenna lever arm: EKF2_GPS_POS_X, EKF2_GPS_POS_Y, EKF2_GPS_POS_Z (m).

If GPS height should drive altitude, use EKF2_HGT_REF = GPS. Otherwise keep Baro (common) and fuse GPS as aiding only.


5) General EKF2 behavior that indirectly impacts position

  • Complementary filter time constants:
    • EKF2_TAU_POS, EKF2_TAU_VEL — response vs. smoothness tradeoff.
  • Fusion horizon / max delay:
    • EKF2_DELAY_MAX — must be ≥ the largest *_DELAY you set.
  • “No aiding” timeout:
    • EKF2_NOAID_TOUT — switches to dead-reckoning if vision/GPS stops. (Documented in EKF tuning guides around estimator behavior.)

6) Quick recipes

A) Vision-only indoor

EKF2_GPS_CTRL = 0 # disable GNSS aiding EKF2_EV_CTRL = (enable Horizontal Pos + 3D Vel + Yaw [+ Vertical Pos if you want Z]) EKF2_HGT_REF = Vision # let vision define height EKF2_EV_DELAY ≈ 0.03–0.08 s # per your pipeline EKF2_EVP_NOISE / EKF2_EVV_NOISE / EKF2_EVA_NOISE tuned for your VIO

(Use external-vision setup guide for exact bit mapping in EV_CTRL.)

B) GPS + Vision (outdoors, smoother position with VIO)

EKF2_GPS_CTRL = (enable Position + Velocity [+ Yaw if dual-antenna]) EKF2_EV_CTRL = (enable Horizontal Pos + 3D Vel + Yaw) EKF2_HGT_REF = GPS or Baro # typical outdoors

(Keep vision Z disabled unless you really want it.)

C) GPS-only

EKF2_GPS_CTRL = enable Position + Velocity EKF2_HGT_REF = GPS or Baro # choose your altitude reference


7) Parameter name sanity check (v1.14)

  • Older names you might see (NOT used in v1.14):
    • EKF2_AID_MASKuse EKF2_GPS_CTRL, EKF2_EV_CTRL, etc.
    • EKF2_HGT_MODEuse EKF2_HGT_REF.

References

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors