From 0677965524e78f805362fcc877377c1889bfcbaa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Jul 2022 13:33:35 +1000 Subject: [PATCH] autotest: adjust PAUSE_CONTINUE_GUIDED to use globalframe for navigation Co-author: Leonard Hall This test was failing when the yaw control on the simulated vehicle was cleaned up. Navigating in body frame meant that the vehicle was told to go to a different position than we were actually expecting. --- Tools/autotest/arducopter.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index e9c972753a..430fa9d740 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -8283,15 +8283,15 @@ class AutoTestCopter(AutoTest): # move vehicle on x direction location = self.offset_location_ne(location=self.mav.location(), metres_north=0, metres_east=-300) - self.mav.mav.set_position_target_local_ned_send( + self.mav.mav.set_position_target_global_int_send( 0, # system time in milliseconds 1, # target system 1, # target component - mavutil.mavlink.MAV_FRAME_BODY_NED, # coordinate frame MAV_FRAME_BODY_NED + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, # coordinate frame MAV_FRAME_BODY_NED MAV_POS_TARGET_TYPE_MASK.POS_ONLY, # type mask (pos only) - 300, # position x - 0, # position y - 0, # position z + int(location.lat*1e7), # position x + int(location.lng*1e7), # position y + 30, # position z 0, # velocity x 0, # velocity y 0, # velocity z