autotest: use guided mode to move Rover away for Dock test

This commit is contained in:
Shiv Tyagi 2022-09-19 11:09:37 +05:30 committed by Peter Barker
parent b5be0dcd14
commit a4c88ab2c0
1 changed files with 5 additions and 7 deletions

View File

@ -6049,8 +6049,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
})
start = self.mav.location()
target = start
(target.lat, target.lng) = mavextra.gps_offset(start.lat, start.lng, 4, -4)
target = self.offset_location_ne(start, 50, 0)
self.progress("Setting target to %f %f" % (start.lat, start.lng))
stopping_dist = 0.5
@ -6072,14 +6071,13 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
try:
self.set_parameter("SIM_PLD_TYPE", type)
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
self.arm_vehicle()
self.reach_heading_manual(0)
self.set_rc(3, 1400)
self.wait_distance(25)
self.set_rc_default()
initial_position = self.offset_location_ne(target, -20, -2)
self.drive_to_location(initial_position)
self.change_mode(8) # DOCK mode
self.wait_groundspeed(0, 0.03, timeout=120)
self.wait_distance_to_location(target, 0, 0.5, timeout=120)
self.disarm_vehicle()
self.assert_receive_message('GLOBAL_POSITION_INT')
new_pos = self.mav.location()