Browse Source

Tools: autotest: use change_mode in apmrover2 for changing modes

master
Peter Barker 6 years ago committed by Peter Barker
parent
commit
e6c30f6405
  1. 15
      Tools/autotest/apmrover2.py
  2. 5
      Tools/autotest/common.py

15
Tools/autotest/apmrover2.py

@ -400,8 +400,7 @@ class AutoTestRover(AutoTest): @@ -400,8 +400,7 @@ class AutoTestRover(AutoTest):
self.set_parameter('CRUISE_SPEED', speed*1.2)
# at time of writing, the vehicle is only capable of 10m/s/s accel
self.set_parameter('ATC_ACCEL_MAX', 15)
self.mavproxy.send("mode STEERING\n")
self.wait_mode('STEERING')
self.change_mode("STEERING")
self.set_rc(3, 2000)
self.wait_groundspeed(15, 100)
initial = self.mav.location()
@ -530,17 +529,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) @@ -530,17 +529,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.arm_vehicle()
# first make sure we can breach the fence:
self.set_rc(10, 1000)
self.mavproxy.send("mode acro\n")
self.wait_mode("ACRO")
self.change_mode("ACRO")
self.set_rc(3, 1550)
self.wait_distance_home_gt(25)
self.mavproxy.send("mode RTL\n")
self.wait_mode("RTL")
self.change_mode("RTL")
self.mavproxy.expect("APM: Reached destination")
# now enable avoidance and make sure we can't:
self.set_rc(10, 2000)
self.mavproxy.send("mode acro\n")
self.wait_mode("ACRO")
self.change_mode("ACRO")
self.wait_groundspeed(0, 0.7, timeout=60)
# watch for speed zero
self.wait_groundspeed(0, 0.2, timeout=120)
@ -752,8 +748,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) @@ -752,8 +748,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
try:
self.load_mission("rover-camera-mission.txt")
self.wait_ready_to_arm()
self.mavproxy.send('mode auto\n')
self.wait_mode('AUTO')
self.change_mode("AUTO")
self.wait_ready_to_arm()
self.arm_vehicle()
prev_cf = None

5
Tools/autotest/common.py

@ -893,6 +893,11 @@ class AutoTest(ABC): @@ -893,6 +893,11 @@ class AutoTest(ABC):
bearing += 360.00
return bearing
def change_mode(self, mode):
'''change vehicle flightmode'''
self.mavproxy.send('mode %s\n' % mode)
self.wait_mode(mode)
def do_get_autopilot_capabilities(self):
tstart = self.get_sim_time()
while self.get_sim_time() - tstart < 10:

Loading…
Cancel
Save