mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: send position targets once
This commit is contained in:
parent
d13f6acc66
commit
750f1d4032
@ -3056,9 +3056,6 @@ class AutoTestCopter(AutoTest):
|
||||
"""stop the vehicle moving in guided mode"""
|
||||
self.progress("Stopping vehicle")
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
raise NotAchievedException("Vehicle did not stop")
|
||||
# send a position-control command
|
||||
self.mav.mav.set_position_target_local_ned_send(
|
||||
0, # timestamp
|
||||
@ -3078,6 +3075,9 @@ class AutoTestCopter(AutoTest):
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
raise NotAchievedException("Vehicle did not stop")
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
print("%s" % str(m))
|
||||
if (m.groundspeed < groundspeed_tolerance and
|
||||
@ -3088,11 +3088,6 @@ class AutoTestCopter(AutoTest):
|
||||
startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
||||
blocking=True)
|
||||
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > 200:
|
||||
raise NotAchievedException("Did not move far enough")
|
||||
# send a position-control command
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0, # timestamp
|
||||
1, # target system_id
|
||||
@ -3111,6 +3106,12 @@ class AutoTestCopter(AutoTest):
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > 200:
|
||||
raise NotAchievedException("Did not move far enough")
|
||||
# send a position-control command
|
||||
pos = self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
||||
blocking=True)
|
||||
delta = self.get_distance_int(startpos, pos)
|
||||
@ -3124,9 +3125,6 @@ class AutoTestCopter(AutoTest):
|
||||
self.progress("startpos=%s" % str(startpos))
|
||||
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
raise NotAchievedException("Did not start to move")
|
||||
# send a position-control command
|
||||
self.mav.mav.set_position_target_local_ned_send(
|
||||
0, # timestamp
|
||||
@ -3146,6 +3144,9 @@ class AutoTestCopter(AutoTest):
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
raise NotAchievedException("Did not start to move")
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
print("%s" % m)
|
||||
if m.groundspeed > 0.5:
|
||||
@ -4410,9 +4411,6 @@ class AutoTestCopter(AutoTest):
|
||||
def fly_guided_move_to(self, destination, timeout=30):
|
||||
'''move to mavutil.location location; absolute altitude'''
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time() - tstart > timeout:
|
||||
raise NotAchievedException()
|
||||
self.mav.mav.set_position_target_global_int_send(
|
||||
0, # timestamp
|
||||
1, # target system_id
|
||||
@ -4431,6 +4429,9 @@ class AutoTestCopter(AutoTest):
|
||||
0, # yaw
|
||||
0, # yawrate
|
||||
)
|
||||
while True:
|
||||
if self.get_sim_time() - tstart > timeout:
|
||||
raise NotAchievedException()
|
||||
delta = self.get_distance(self.mav.location(), destination)
|
||||
self.progress("delta=%f (want <1)" % delta)
|
||||
if delta < 1:
|
||||
|
Loading…
Reference in New Issue
Block a user