mirror of https://github.com/ArduPilot/ardupilot
Tools: put Mission files into right directories
This commit is contained in:
parent
04d760d54c
commit
5b26df5780
|
@ -873,7 +873,7 @@ class AutoTest(ABC):
|
|||
|
||||
def load_fence_using_mavproxy(self, filename):
|
||||
self.set_parameter("FENCE_TOTAL", 0)
|
||||
filepath = os.path.join(self.mission_directory(), filename)
|
||||
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
|
||||
count = self.count_expected_fence_lines_in_filepath(filepath)
|
||||
self.mavproxy.send('fence load %s\n' % filepath)
|
||||
# self.mavproxy.expect("Loaded %u (geo-)?fence" % count)
|
||||
|
@ -1610,9 +1610,6 @@ class AutoTest(ABC):
|
|||
this_dir = os.path.dirname(__file__)
|
||||
return os.path.realpath(os.path.join(this_dir, "../.."))
|
||||
|
||||
def mission_directory(self):
|
||||
return testdir
|
||||
|
||||
def assert_mission_files_same(self, file1, file2):
|
||||
self.progress("Comparing (%s) and (%s)" % (file1, file2, ))
|
||||
f1 = open(file1)
|
||||
|
@ -1781,7 +1778,7 @@ class AutoTest(ABC):
|
|||
def load_rally(self, filename):
|
||||
"""Load rally points from a file to flight controller."""
|
||||
self.progress("Loading rally points (%s)" % filename)
|
||||
path = os.path.join(self.mission_directory(), filename)
|
||||
path = os.path.join(testdir, self.current_test_name_directory, filename)
|
||||
self.mavproxy.send('rally load %s\n' % path)
|
||||
self.mavproxy.expect("Loaded")
|
||||
|
||||
|
@ -1789,9 +1786,12 @@ class AutoTest(ABC):
|
|||
self.load_mission(self.sample_mission_filename())
|
||||
|
||||
def load_mission(self, filename):
|
||||
return self.load_mission_from_filepath(self.current_test_name_directory, filename)
|
||||
|
||||
def load_mission_from_filepath(self, filepath, filename):
|
||||
"""Load a mission from a file to flight controller."""
|
||||
self.progress("Loading mission (%s)" % filename)
|
||||
path = os.path.join(self.mission_directory(), filename)
|
||||
path = os.path.join(testdir, filepath, filename)
|
||||
tstart = self.get_sim_time_cached()
|
||||
while True:
|
||||
t2 = self.get_sim_time_cached()
|
||||
|
@ -1998,7 +1998,10 @@ class AutoTest(ABC):
|
|||
"""Load arming test mission.
|
||||
This mission is used to allow to change mode to AUTO. For each vehicle
|
||||
it get an unlimited wait waypoint and the starting takeoff if needed."""
|
||||
return None
|
||||
if self.is_rover() or self.is_plane() or self.is_sub():
|
||||
return os.path.join(testdir, self.current_test_name_directory + "test_arming.txt")
|
||||
else:
|
||||
return None
|
||||
|
||||
def armed(self):
|
||||
"""Return true if vehicle is armed and safetyoff"""
|
||||
|
@ -3274,7 +3277,7 @@ class AutoTest(ABC):
|
|||
prettyname = "%s (%s)" % (name, desc)
|
||||
self.send_statustext(prettyname)
|
||||
self.start_test(prettyname)
|
||||
|
||||
self.set_current_test_name(name)
|
||||
self.context_push()
|
||||
|
||||
start_time = time.time()
|
||||
|
|
Loading…
Reference in New Issue