mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Tools: autotest: use change_mode in apmrover2 for changing modes
This commit is contained in:
parent
a320a54f66
commit
e6c30f6405
@ -400,8 +400,7 @@ class AutoTestRover(AutoTest):
|
|||||||
self.set_parameter('CRUISE_SPEED', speed*1.2)
|
self.set_parameter('CRUISE_SPEED', speed*1.2)
|
||||||
# at time of writing, the vehicle is only capable of 10m/s/s accel
|
# at time of writing, the vehicle is only capable of 10m/s/s accel
|
||||||
self.set_parameter('ATC_ACCEL_MAX', 15)
|
self.set_parameter('ATC_ACCEL_MAX', 15)
|
||||||
self.mavproxy.send("mode STEERING\n")
|
self.change_mode("STEERING")
|
||||||
self.wait_mode('STEERING')
|
|
||||||
self.set_rc(3, 2000)
|
self.set_rc(3, 2000)
|
||||||
self.wait_groundspeed(15, 100)
|
self.wait_groundspeed(15, 100)
|
||||||
initial = self.mav.location()
|
initial = self.mav.location()
|
||||||
@ -530,17 +529,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
# first make sure we can breach the fence:
|
# first make sure we can breach the fence:
|
||||||
self.set_rc(10, 1000)
|
self.set_rc(10, 1000)
|
||||||
self.mavproxy.send("mode acro\n")
|
self.change_mode("ACRO")
|
||||||
self.wait_mode("ACRO")
|
|
||||||
self.set_rc(3, 1550)
|
self.set_rc(3, 1550)
|
||||||
self.wait_distance_home_gt(25)
|
self.wait_distance_home_gt(25)
|
||||||
self.mavproxy.send("mode RTL\n")
|
self.change_mode("RTL")
|
||||||
self.wait_mode("RTL")
|
|
||||||
self.mavproxy.expect("APM: Reached destination")
|
self.mavproxy.expect("APM: Reached destination")
|
||||||
# now enable avoidance and make sure we can't:
|
# now enable avoidance and make sure we can't:
|
||||||
self.set_rc(10, 2000)
|
self.set_rc(10, 2000)
|
||||||
self.mavproxy.send("mode acro\n")
|
self.change_mode("ACRO")
|
||||||
self.wait_mode("ACRO")
|
|
||||||
self.wait_groundspeed(0, 0.7, timeout=60)
|
self.wait_groundspeed(0, 0.7, timeout=60)
|
||||||
# watch for speed zero
|
# watch for speed zero
|
||||||
self.wait_groundspeed(0, 0.2, timeout=120)
|
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)
|
|||||||
try:
|
try:
|
||||||
self.load_mission("rover-camera-mission.txt")
|
self.load_mission("rover-camera-mission.txt")
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.mavproxy.send('mode auto\n')
|
self.change_mode("AUTO")
|
||||||
self.wait_mode('AUTO')
|
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.arm_vehicle()
|
self.arm_vehicle()
|
||||||
prev_cf = None
|
prev_cf = None
|
||||||
|
@ -893,6 +893,11 @@ class AutoTest(ABC):
|
|||||||
bearing += 360.00
|
bearing += 360.00
|
||||||
return bearing
|
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):
|
def do_get_autopilot_capabilities(self):
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while self.get_sim_time() - tstart < 10:
|
while self.get_sim_time() - tstart < 10:
|
||||||
|
Loading…
Reference in New Issue
Block a user