From 5c4983ffcd5204d83250632ba171870cfe24080b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Apr 2019 11:56:44 +1100 Subject: [PATCH] GCS_MAVLink: stop converting compass cal floats to ints before saving --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 87267aede2..77809adccb 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3315,7 +3315,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlin if (compassNumber == (uint8_t) -1) { return MAV_RESULT_FAILED; } - compass.set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4); + compass.set_and_save_offsets(compassNumber, Vector3f(packet.param2, packet.param3, packet.param4)); return MAV_RESULT_ACCEPTED; }