mirror of https://github.com/ArduPilot/ardupilot
autotest: rename do_reposition to send_do_reposition
This commit is contained in:
parent
0179dc0a68
commit
1de60a31b0
|
@ -11517,7 +11517,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
here = self.mav.location()
|
||||
loc = self.offset_location_ne(here, 10, 0)
|
||||
self.takeoff(5, mode='GUIDED')
|
||||
self.do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL)
|
||||
self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL)
|
||||
self.wait_location(loc, timeout=120)
|
||||
self.land_and_disarm()
|
||||
|
||||
|
|
|
@ -1895,7 +1895,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.install_message_hook_context(terrain_following_above_80m)
|
||||
|
||||
self.change_mode("GUIDED")
|
||||
self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
|
||||
self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
|
||||
self.progress("Flying to guided location")
|
||||
self.wait_location(
|
||||
guided_loc,
|
||||
|
@ -1918,7 +1918,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
|
||||
# Fly back to guided location
|
||||
self.change_mode("GUIDED")
|
||||
self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
|
||||
self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
|
||||
self.progress("Flying to back to guided location")
|
||||
|
||||
# Disable terrain following and re-load rally point with relative to terrain altitude
|
||||
|
|
|
@ -862,13 +862,13 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
|||
guided_loc = self.home_relative_loc_ne(0, 0)
|
||||
guided_loc.alt = 60
|
||||
self.change_mode("GUIDED")
|
||||
self.do_reposition(guided_loc)
|
||||
self.send_do_reposition(guided_loc)
|
||||
self.wait_altitude(58, 62, relative=True)
|
||||
self.set_parameter("Q_ASSIST_ALT", 50)
|
||||
|
||||
# Try and descent to 40m
|
||||
guided_loc.alt = 40
|
||||
self.do_reposition(guided_loc)
|
||||
self.send_do_reposition(guided_loc)
|
||||
|
||||
# Expect alt assist to kick in, eg "Alt assist 48.9m"
|
||||
self.wait_statustext(r"Alt assist \d*.\d*m", regex=True, timeout=100)
|
||||
|
|
|
@ -7884,7 +7884,7 @@ class TestSuite(ABC):
|
|||
raise NotAchievedException("Expected %s to be %u got %u" %
|
||||
(channel, value, m_value))
|
||||
|
||||
def do_reposition(self,
|
||||
def send_do_reposition(self,
|
||||
loc,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT):
|
||||
'''send a DO_REPOSITION command for a location'''
|
||||
|
|
Loading…
Reference in New Issue