From 82cf8a93d0d5c4fc536ad6601d88c4f62d16789e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 27 Jul 2019 11:38:16 +1000 Subject: [PATCH] Rover: use MAV_FRAME_GLOBAL instead of MAV_FRAME_GLOBAL_INT in send_position_target --- APMrover2/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 9d23bfb5c0..3cab4b3b3e 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -82,7 +82,7 @@ void GCS_MAVLINK_Rover::send_position_target_global_int() mavlink_msg_position_target_global_int_send( chan, AP_HAL::millis(), // time_boot_ms - MAV_FRAME_GLOBAL_INT, // targets are always global altitude + MAV_FRAME_GLOBAL, // targets are always global altitude 0xFFF8, // ignore everything except the x/y/z components target.lat, // latitude as 1e7 target.lng, // longitude as 1e7