mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
GCS_MAVLink: stop converting compass cal floats to ints before saving
This commit is contained in:
parent
7ae7c48362
commit
5c4983ffcd
@ -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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user