Fake NMEA Signal Causes Velocity to Drop to 0

I am creating a fake NMEA Signal and passing to ArduPilot. Positioning seems to work great, but the velocity continuously drops to 0 before going back up, causing EKF Variance & making it impossible to fly.

I’m currently looking at an approach that avoids this using MavLink like here: Intel RealSense T265 — Copter documentation - however long term I would like to be able to send NMEA in in a way that does not cause issues.

These are global positions, calculated using a VIO and known to be accurate - I can plot them on a map, or even look at ardupilot and see the position is correct, the issue appears to be in the velocity.

Help much appreciated!

NMEA Sentences Look Like:

    def lat_lon_to_nmea(self, lat, lon, alt, speed, course):
        timestamp = self.get_utc_timestamp()
        date = self.get_utc_date()

        # Convert latitude to degrees and minutes
        lat_deg = int(abs(lat))
        lat_min = (abs(lat) - lat_deg) * 60
        lat_str = f"{lat_deg:02d}{lat_min:09.6f}"

        # Convert longitude to degrees and minutes
        lon_deg = int(abs(lon))
        lon_min = (abs(lon) - lon_deg) * 60
        lon_str = f"{lon_deg:03d}{lon_min:09.6f}"

        # Create GGA sentence
        gga_msg = pynmea2.GGA(
            "GP",
            "GGA",
            (
                timestamp,
                lat_str,
                "N" if lat >= 0 else "S",
                lon_str,
                "E" if lon >= 0 else "W",
                "1",  # Fix quality: 1 = GPS fix
                "20",  # Number of satellites
                ".7",  # HDOP
                f"{alt:.1f}",  # Altitude
                "M",  # Altitude units (meters)
                "1",  # Height of geoid above WGS84 ellipsoid
                "M",  # Units (meters)
                "",  # Time since last DGPS update (empty for GPS)
                "",  # DGPS reference station id (empty for GPS)
            ),
        )
        # Create RMC sentence
        rmc_msg = pynmea2.RMC(
            "GP",
            "RMC",
            (
                timestamp,
                "A",  # Status A=active or V=void
                lat_str,
                "N" if lat >= 0 else "S",
                lon_str,
                "E" if lon >= 0 else "W",
                f"{speed:.2f}",  # Speed over ground in knots
                f"{course:.2f}",  # Course over ground in degrees
                date,  # Date
                "0.0",  # Magnetic variation
                "",  # Magnetic variation direction
                "A",  # Mode indicator
            ),
        )

        return f"{gga_msg.render()}\r\n{rmc_msg.render()}\r\n"
        # return f"{rmc_msg.render()}\r\n"

An example from logs:
image

Can you check if you are sending “doubles” (two packets containing the same position?

How often are you sending messages?

Oh this is quite a good point. I’ve been playing around with frequency- I actually increased it (and therefore doubles) while diagnosing this. I guess I should only be sending info when there’s a change! This makes a lot of sense, lol

IIRC EKF needs GPS messages at 5-10 Hz otherwise it gets quite unhappy especially going below 5Hz.

It wouldn’t be from too few messages. If anything we were sending too many.

Here’s some sample messages:

There is variation- I’m confused why they aren’t being integrated properly. Maybe I am mocking something improperly or need to further configure params?

Broadcasting:
$GPGGA,214655.07,3809.283851,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*61
$GPRMC,214655.07,A,3809.283851,N,12230.711516,W,0.05,0.00,080724,0.0,,A*68
Broadcasting:
$GPGGA,214655.13,3809.283852,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*67
$GPRMC,214655.13,A,3809.283852,N,12230.711516,W,0.05,0.00,080724,0.0,,A*6E
Speed 0.021825516189920017
Distance 0.005822056364594712
Broadcasting:
$GPGGA,214655.32,3809.283852,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*64
$GPRMC,214655.32,A,3809.283852,N,12230.711516,W,0.02,0.00,080724,0.0,,A*6A
Broadcasting:
$GPGGA,214655.39,3809.283845,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*69
$GPRMC,214655.39,A,3809.283845,N,12230.711516,W,0.02,0.00,080724,0.0,,A*67
Broadcasting:
$GPGGA,214655.58,3809.283845,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*6E
$GPRMC,214655.58,A,3809.283845,N,12230.711516,W,0.02,0.00,080724,0.0,,A*60
Broadcasting:
$GPGGA,214655.65,3809.283845,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*60
$GPRMC,214655.65,A,3809.283845,N,12230.711516,W,0.02,0.00,080724,0.0,,A*6E
Speed 0.05746267695494502
Distance 0.015598749750773145
Broadcasting:
$GPGGA,214655.85,3809.283845,N,12230.711516,W,1,20,.7,1.2,M,1,M,,*6E
$GPRMC,214655.85,A,3809.283845,N,12230.711516,W,0.06,0.00,080724,0.0,,A*64
Broadcasting:
$GPGGA,214655.91,3809.283845,N,12230.711516,W,1,20,.7,1.1,M,1,M,,*68
$GPRMC,214655.91,A,3809.283845,N,122

I’m going to try disabling EK3_SRC1_VELXY and see what happens