Why decrease EKF2_GPS_V_NOISE and EKF2_GPS_P_NOISE Parameters when using RTK GPS

Hello,
as desribed at https://docs.px4.io/master/en/gps_compass/rtk_gps.html one should decrease those two parameters when using the RTK GPS. In my understanding this is due to the fact, that the RTK GPS is way more accurate than a normal one and therefore the Pixhawk shouldn’t assume such a big noise.

My question is where exactly are these parameter changes taken into account? Meaning how does the PX4 act different when using a smaller noise in comparison to a bigger one?
And how much should I decrease this parameters when using the RTK?

Thanks a lot.
Best regards,
Fabian

Hi @sofa03 ,

PX4 fuses the GPS position and velocity data in an extended Kalman filter (named ekf2), weighting each measurement with its expected noise. In case of GPS, the receiver also reports an estimated accuracy (eph, epv) and are used by the filter. However, to prevent fusing incorrect data from an over-optimistic receiver, the minimum reported noise is limited using two parameters: EKF2_GPS_P_NOISE and EKF2_GPS_V_NOISE for the position and velocity measurements, respectively.
Their default values are good for most common GNSS receivers, but are too large when having additional RTK correction. For this reason, you can reduce those parameters depending of the level of accuracy of your receiver to get better results.

1 Like

Hi @bresch,

First of all thanks for your answer. The GPS receiver reports the accuracy, but isn’t the estimated accuracy the fields h_acc and v_acc of Mavlink message GPS_RAW_INT #24 instead of eph and epv? Because eph and epv just give me an idea reagarding the constellation of satellites, right?
Or do you know, if h_acc and v_acc are calculated by taking epv and eph into account?
Thanks.

Yes and no, the issue here is that there is a really annoying error in that MAVLink message (https://github.com/mavlink/mavlink/issues/1063):

Description PX4 MAVLink
Position accuracy (m) eph, epv h_acc, v_acc
Dilution of precision (-) hdop, vdop eph, epv
Speed accuracy (m/s) s_variance_m_s vel_acc

(MAVLink uses eph, epv incorrectly and in PX4, s_variance_m_s is actually a standard deviation and not a variance)

So, when I said eph, epv, I actually meant “position accuracy” (h_acc, v_acc in MAVLink).

MAVLink msg: https://mavlink.io/en/messages/common.html#GPS_RAW_INT
PX4 msg: https://github.com/PX4/PX4-Autopilot/blob/master/msg/vehicle_gps_position.msg

1 Like

One more question that came to my mind today:
In my understanding the RTCM messages providing the correction by the RTK base are processed by the GPS module itself and therefore the h_acc(eph) and v_acc (epv) are already calculated using the corrected position?

This would result in the ekf2 of PX4 not taking the RTCM messages as input, as they have already been merged into the GPS Position by the GNSS.

Concluding the h_acc and v_acc only provide an accuracy estimation before the ekf2. Is there a way to get some kind of accuracy estimation following the ekf2?

Yes

Correct

Yes, the accuracy of the state estimate can be found in:

Okay, thanks a lot.

I can receive and process the MAVLink message using my Mission Software, so thats the message I wll work with. As my experience with covariance is very limited, which element of the array in the covariance field acutally holds the estimated accuracy value?