From 65557bfa8d350bc45b3f7a321818354b29b1f379 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Mon, 17 Jan 2022 13:56:09 -0300 Subject: [PATCH] ardupilotmega: use params 6 and 7 of MAV_CMD_DO_START_MAG_CAL to pass lon/lat This will improve the calibration of compasses on vehicles not equipped with a GPS. As `fix_radius()` in step two of calibration requires a GPS lock. --- message_definitions/v1.0/ardupilotmega.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/message_definitions/v1.0/ardupilotmega.xml b/message_definitions/v1.0/ardupilotmega.xml index b98ad3de1a..165ff8c403 100644 --- a/message_definitions/v1.0/ardupilotmega.xml +++ b/message_definitions/v1.0/ardupilotmega.xml @@ -158,8 +158,8 @@ Save without user input (0=require input, 1=autosave). Delay. Autoreboot (0=user reboot, 1=autoreboot). - Empty. - Empty. + Latitude where calibration is happening, for vehicles with no GPS (0 means ignore). + Longitude where calibration is happening, for vehicles with no GPS (0 means ignore). Accept a magnetometer calibration.