Send GPS data via Mavlink to ardupilot

Hi everyone. I’m using ArduCopter 4.2.2 and trying to send GPS data via Mavlink.
I use “dronekit” library to send GPS messages via Mavlink to Ardupilot with a USB cable.
my function is here:

def send_gps_raw(lat,lon,alt):
msg = vehicle.message_factory.gps_input_encode(
0, # Timestamp (micros since boot or Unix epoch)
0, # ID of the GPS for multiple GPS inputs
# Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum).
# All other fields must be provided.
(mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VEL_HORIZ |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VEL_VERT |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY) |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY,
0, # GPS time (milliseconds from start of GPS week)
0, # GPS week number
3, # 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
int(lat1e7), # Latitude (WGS84), in degrees * 1E7
int(lon
1e7), # Longitude (WGS84), in degrees * 1E7
alt, # Altitude (AMSL, not WGS84), in m (positive for up)
0.4, # GPS HDOP horizontal dilution of position in m
1.4, # GPS VDOP vertical dilution of position in m
0, # GPS velocity in m/s in NORTH direction in earth-fixed NED frame
0, # GPS velocity in m/s in EAST direction in earth-fixed NED frame
0, # GPS velocity in m/s in DOWN direction in earth-fixed NED frame
0, # GPS speed accuracy in m/s
0, # GPS horizontal accuracy in m
0, # GPS vertical accuracy in m
24 # Number of satellites visible.
)
vehicle.send_mavlink(msg)

all data has been ignored except lat, long, and HDOP. for generating lat, long, and HDOP I used UBLOX GPS connected to my PC.
I extracted GPS data via the pynmea2 library in python.
I set GPS_TYPE =14(MAV) in the parameters.
after this configuration when I ran the code GPS status was shown in MP(Its image is attached below).
When I want to ARM the vehicle in “PosHold” mode this error is displayed on MP: GPS1 is unhealthy.
What should I do?
Can anyone help me, please?

@WickedShell
@rmackay9
Can you please help me?

@A_manafi,

It is a guess but I wonder if maybe the mavlink messages aren’t being sent quickly enough? they need to be sent at 5hz (or higher)…

Hi all,

i´m using Arducopter 4.5.7. and also trying to send GPS data via MAVlink using pymavlink.
My problem is, that the outgoing data is completely ignored no matter what i try.
Heartbeat is healthy all the time.

Does anybody have an idea how to solve the problem?
Many thanks!

import time
from pymavlink import mavutil
from datetime import datetime
import logging

# Set up logging for error tracking and debugging
logging.basicConfig(filename='pixhawk_log.txt', level=logging.INFO, format='%(asctime)s - %(levelname)s - %(message)s')

# Define the GPS epoch (January 6, 1980)
GPS_EPOCH = datetime(1980, 1, 6)

# Define the connection to the Pixhawk (
try:
    connection = mavutil.mavlink_connection('/dev/ttyTHS0', baud=57600, source_system=2, source_component=mavutil.mavlink.MAV_COMP_ID_GPS2)
    logging.info("Connection to Pixhawk established successfully.")
except Exception as e:
    logging.error(f"Failed to connect to Pixhawk: {e}")
    raise SystemExit

def get_gps_time():
    # Calculate the GPS week number and milliseconds into the week
    now = datetime.utcnow()
    delta = now - GPS_EPOCH
    gps_week = delta.days // 7
    gps_week_ms = ((delta.days % 7) * 24 * 60 * 60 + delta.seconds) * 1000 + int(delta.microseconds / 1000)
    return gps_week, gps_week_ms

def send_gps_input():
    try:
        # Define the GPS data as per your format
        gps_week, gps_week_ms = get_gps_time()
        
        data = {
            'time_usec': int(time.time() * 1e6),  # Timestamp (microseconds since system boot)
            'fix_type': 3,  # 3D fix (0-1: no fix, 2: 2D fix, 3: 3D fix)
            'lat': 374220000,  # Latitude (degrees * 1E7, realistic value for San Francisco, CA)
            'lon': -1220840000,  # Longitude (degrees * 1E7, realistic value for San Francisco, CA)
            'alt': 15000,  # Altitude (millimeters above mean sea level, 15 meters)
            'eph': 50,  # Horizontal dilution of precision (in cm, realistic value)
            'epv': 50,  # Vertical dilution of precision (in cm, realistic value)
            'vel': 500,  # GPS velocity (cm/s, 5 m/s, realistic movement speed)
            'cog': 9000,  # Course over ground (degrees * 100, 90 degrees, facing east)
            'satellites_visible': 10,  # Number of visible satellites (typical value for good GPS signal)
            'alt_ellipsoid': 15000,  # Altitude above ellipsoid (millimeters, same as altitude)
            'h_acc': 300,  # Horizontal accuracy (mm, realistic value)
            'v_acc': 300,  # Vertical accuracy (mm, realistic value)
            'vel_acc': 200,  # Velocity accuracy (mm, realistic value)
            'hdg_acc': 5000,  # Heading accuracy (deg * 1E5, realistic value)
            'gps_instance': 1  # GPS instance being reported (1 for GPS2)
        }

        # Send the GPS_RAW_INT MAVLink message using the data
        connection.mav.gps_raw_int_send(
            data['time_usec'],        # Timestamp (microseconds since boot)
            data['fix_type'],         # Fix type (0-1: no fix, 2: 2D fix, 3: 3D fix)
            data['lat'],              # Latitude (degrees * 1E7)
            data['lon'],              # Longitude (degrees * 1E7)
            data['alt'],              # Altitude (millimeters above mean sea level)
            data['eph'],              # GPS horizontal dilution of precision (in cm)
            data['epv'],              # GPS vertical dilution of precision (in cm)
            data['vel'],              # GPS ground speed (cm/s)
            data['cog'],              # Course over ground (degrees * 100)
            data['satellites_visible']  # Number of visible satellites
        )
        logging.info("GPS_RAW_INT data sent as GPS instance 1 (secondary GPS).")
    except Exception as e:
        logging.error(f"Failed to send GPS_RAW_INT: {e}")

# Main function to send GPS data at regular intervals
def main():
    while True:
        # Send the GPS_RAW_INT message
        send_gps_input()
        # Sleep for 0.5 seconds to send data at 2 Hz
        time.sleep(0.2)  # data rate of 5 Hz for GPS

if __name__ == "__main__":
    try:
        main()
    except KeyboardInterrupt:
        logging.info("Script interrupted by user. Exiting...")
    except Exception as e:
        logging.error(f"Unexpected error: {e}")
        raise SystemExit