autotest: use self.set_current_waypoint rather than "wp set" to set current wp

This commit is contained in:
Peter Barker 2021-02-18 21:32:49 +11:00 committed by Peter Barker
parent 148e2e751f
commit c13d229877
4 changed files with 15 additions and 16 deletions

View File

@ -410,7 +410,7 @@ class AutoTestCopter(AutoTest):
self.progress("save_mission_to_file failed")
self.progress("test: Fly a mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_waypoint(0, num_wp-1, timeout=500)
self.progress("test: MISSION COMPLETE: passed!")
@ -1450,7 +1450,7 @@ class AutoTestCopter(AutoTest):
self.show_gps_and_sim_positions(True)
self.progress("test: Fly a mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
self.set_current_waypoint(1)
self.change_mode("STABILIZE")
self.wait_ready_to_arm()
@ -1971,7 +1971,7 @@ class AutoTestCopter(AutoTest):
raise NotAchievedException("load copter_mission failed")
self.progress("test: Fly a mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
self.set_current_waypoint(1)
self.change_mode("LOITER")
self.wait_ready_to_arm()
@ -5551,9 +5551,7 @@ class AutoTestCopter(AutoTest):
self.delay_sim_time(2)
self.load_mission("copter_loiter_to_alt.txt")
set_wp = 4
self.mavproxy.send("wp set %u\n" % set_wp)
self.delay_sim_time(1)
self.drain_mav()
self.set_current_waypoint(set_wp)
self.wait_current_waypoint(set_wp, timeout=10)
self.progress("Reset mission")
self.set_rc(7, 2000)
@ -6783,7 +6781,7 @@ class AutoTestHeli(AutoTestCopter):
raise NotAchievedException("load copter_AVC2013_mission failed")
self.progress("Fly AVC mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
self.set_current_waypoint(1)
# wait for motor runup
self.delay_sim_time(20)

View File

@ -705,7 +705,7 @@ class AutoTestPlane(AutoTest):
self.progress("Using %s to fly home" % filename)
self.load_mission(filename)
self.change_mode("AUTO")
self.mavproxy.send('wp set 7\n')
self.set_current_waypoint(7)
self.drain_mav()
# TODO: reflect on file to find this magic waypoint number?
# self.wait_waypoint(7, num_wp-1, timeout=500) # we
@ -759,7 +759,7 @@ class AutoTestPlane(AutoTest):
self.progress("Flying mission %s" % filename)
self.load_mission(filename)
self.mavproxy.send('wp set 1\n')
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
@ -1019,7 +1019,7 @@ class AutoTestPlane(AutoTest):
ex = None
try:
self.load_mission("plane-gripper-mission.txt")
self.mavproxy.send("wp set 1\n")
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
@ -1277,7 +1277,7 @@ class AutoTestPlane(AutoTest):
self.set_parameter("SIM_PARA_PIN", 9)
self.load_mission("plane-parachute-mission.txt")
self.mavproxy.send("wp set 1\n")
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
@ -1507,7 +1507,7 @@ class AutoTestPlane(AutoTest):
'''ensure rangefinder gives height-above-ground'''
self.load_mission("plane-gripper-mission.txt") # borrow this
self.mavproxy.send("wp set 1\n")
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
@ -1816,7 +1816,7 @@ class AutoTestPlane(AutoTest):
self.load_mission('CMAC-soar.txt')
self.mavproxy.send("wp set 1\n")
self.set_current_waypoint(1)
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
@ -1923,7 +1923,7 @@ class AutoTestPlane(AutoTest):
def fly_terrain_mission(self):
self.mavproxy.send("wp set 1\n")
self.set_current_waypoint(1)
self.wait_ready_to_arm()
self.arm_vehicle()

View File

@ -275,7 +275,7 @@ class AutoTestQuadPlane(AutoTest):
self.wait_disarmed(timeout=120) # give quadplane a long time to land
# wait for blood sample here
self.mavproxy.send('wp set 20\n')
self.set_current_waypoint(20)
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
@ -343,7 +343,7 @@ class AutoTestQuadPlane(AutoTest):
self.progress("Using %s to fly home" % filename)
self.load_mission(filename)
self.change_mode("AUTO")
self.mavproxy.send('wp set 7\n')
self.set_current_waypoint(7)
self.wait_disarmed(timeout=timeout)
def wait_level_flight(self, accuracy=5, timeout=30):

View File

@ -3556,6 +3556,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.reboot_sitl()
def test_gcs_mission(self):
'''check MAVProxy's waypoint handling of missions'''
target_system = 1
target_component = 1
self.mavproxy.send('wp clear\n')