GCS_MAVLink: stop converting compass cal floats to ints before saving

This commit is contained in:
Peter Barker 2019-04-04 11:56:44 +11:00 committed by Tom Pittenger
parent 7ae7c48362
commit 5c4983ffcd

View File

@ -3315,7 +3315,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlin
if (compassNumber == (uint8_t) -1) { if (compassNumber == (uint8_t) -1) {
return MAV_RESULT_FAILED; 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; return MAV_RESULT_ACCEPTED;
} }