|
|
@ -1564,19 +1564,13 @@ class AutoTestCopter(AutoTest): |
|
|
|
|
|
|
|
|
|
|
|
self.load_mission("copter_nav_delay.txt") |
|
|
|
self.load_mission("copter_nav_delay.txt") |
|
|
|
|
|
|
|
|
|
|
|
self.mavproxy.send('mode loiter\n') |
|
|
|
self.set_parameter("DISARM_DELAY", 0) |
|
|
|
self.wait_heartbeat() |
|
|
|
|
|
|
|
self.wait_mode('LOITER') |
|
|
|
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
self.context_push() |
|
|
|
self.change_mode("LOITER") |
|
|
|
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
|
|
|
|
|
|
|
ex = None |
|
|
|
|
|
|
|
try: |
|
|
|
|
|
|
|
self.arm_vehicle() |
|
|
|
self.arm_vehicle() |
|
|
|
self.mavproxy.send('mode auto\n') |
|
|
|
self.change_mode("AUTO") |
|
|
|
self.wait_mode('AUTO') |
|
|
|
|
|
|
|
self.set_parameter("DISARM_DELAY", 0) |
|
|
|
|
|
|
|
self.set_rc(3, 1600) |
|
|
|
self.set_rc(3, 1600) |
|
|
|
count_start = -1 |
|
|
|
count_start = -1 |
|
|
|
count_stop = -1 |
|
|
|
count_stop = -1 |
|
|
@ -1588,19 +1582,20 @@ class AutoTestCopter(AutoTest): |
|
|
|
if now - tstart > 120: |
|
|
|
if now - tstart > 120: |
|
|
|
raise AutoTestTimeoutException("Did not disarm as expected") |
|
|
|
raise AutoTestTimeoutException("Did not disarm as expected") |
|
|
|
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True) |
|
|
|
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True) |
|
|
|
|
|
|
|
at_delay_item = "" |
|
|
|
|
|
|
|
if m.seq == 3: |
|
|
|
|
|
|
|
at_delay_item = "(At delay item)" |
|
|
|
|
|
|
|
if count_start == -1: |
|
|
|
|
|
|
|
count_start = now |
|
|
|
if ((now - last_mission_current_msg) > 1 or m.seq != last_seq): |
|
|
|
if ((now - last_mission_current_msg) > 1 or m.seq != last_seq): |
|
|
|
dist = None |
|
|
|
dist = None |
|
|
|
x = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None) |
|
|
|
x = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None) |
|
|
|
if x is not None: |
|
|
|
if x is not None: |
|
|
|
dist = x.wp_dist |
|
|
|
dist = x.wp_dist |
|
|
|
self.progress("MISSION_CURRENT.seq=%u dist=%s" % |
|
|
|
self.progress("MISSION_CURRENT.seq=%u dist=%s %s" % |
|
|
|
(m.seq, dist)) |
|
|
|
(m.seq, dist, at_delay_item)) |
|
|
|
last_mission_current_msg = self.get_sim_time_cached() |
|
|
|
last_mission_current_msg = self.get_sim_time_cached() |
|
|
|
last_seq = m.seq |
|
|
|
last_seq = m.seq |
|
|
|
if m.seq == 3: |
|
|
|
|
|
|
|
self.progress("At delay item") |
|
|
|
|
|
|
|
if count_start == -1: |
|
|
|
|
|
|
|
count_start = now |
|
|
|
|
|
|
|
if m.seq > 3: |
|
|
|
if m.seq > 3: |
|
|
|
if count_stop == -1: |
|
|
|
if count_stop == -1: |
|
|
|
count_stop = now |
|
|
|
count_stop = now |
|
|
@ -1611,15 +1606,6 @@ class AutoTestCopter(AutoTest): |
|
|
|
if calculated_delay < want_delay: |
|
|
|
if calculated_delay < want_delay: |
|
|
|
raise NotAchievedException("Did not delay for long enough") |
|
|
|
raise NotAchievedException("Did not delay for long enough") |
|
|
|
|
|
|
|
|
|
|
|
except Exception as e: |
|
|
|
|
|
|
|
self.progress("Exception caught") |
|
|
|
|
|
|
|
ex = e |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
self.zero_throttle() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if ex is not None: |
|
|
|
|
|
|
|
raise ex |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def test_rangefinder(self): |
|
|
|
def test_rangefinder(self): |
|
|
|
ex = None |
|
|
|
ex = None |
|
|
|
self.context_push() |
|
|
|
self.context_push() |
|
|
@ -1966,11 +1952,8 @@ class AutoTestCopter(AutoTest): |
|
|
|
|
|
|
|
|
|
|
|
self.load_mission("copter_nav_delay.txt") |
|
|
|
self.load_mission("copter_nav_delay.txt") |
|
|
|
|
|
|
|
|
|
|
|
self.progress("Starting mission") |
|
|
|
self.change_mode("LOITER") |
|
|
|
|
|
|
|
|
|
|
|
self.mavproxy.send('mode loiter\n') # stabilize mode |
|
|
|
|
|
|
|
self.wait_heartbeat() |
|
|
|
|
|
|
|
self.wait_mode('LOITER') |
|
|
|
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
|
|
|
|
|
|
|
delay_item_seq = 3 |
|
|
|
delay_item_seq = 3 |
|
|
@ -1979,13 +1962,8 @@ class AutoTestCopter(AutoTest): |
|
|
|
reset_at_m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True) |
|
|
|
reset_at_m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True) |
|
|
|
reset_at = reset_at_m.time_unix_usec/1000000 |
|
|
|
reset_at = reset_at_m.time_unix_usec/1000000 |
|
|
|
|
|
|
|
|
|
|
|
self.context_push() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
ex = None |
|
|
|
|
|
|
|
try: |
|
|
|
|
|
|
|
self.arm_vehicle() |
|
|
|
self.arm_vehicle() |
|
|
|
self.mavproxy.send('mode auto\n') # stabilize mode |
|
|
|
self.change_mode("AUTO") |
|
|
|
self.wait_mode('AUTO') |
|
|
|
|
|
|
|
self.set_rc(3, 1600) |
|
|
|
self.set_rc(3, 1600) |
|
|
|
count_stop = -1 |
|
|
|
count_stop = -1 |
|
|
|
tstart = self.get_sim_time() |
|
|
|
tstart = self.get_sim_time() |
|
|
@ -1994,9 +1972,10 @@ class AutoTestCopter(AutoTest): |
|
|
|
if now - tstart > 120: |
|
|
|
if now - tstart > 120: |
|
|
|
raise AutoTestTimeoutException("Did not disarm as expected") |
|
|
|
raise AutoTestTimeoutException("Did not disarm as expected") |
|
|
|
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True) |
|
|
|
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True) |
|
|
|
self.progress("MISSION_CURRENT.seq=%u" % (m.seq,)) |
|
|
|
at_delay_item = "" |
|
|
|
if m.seq == delay_item_seq: |
|
|
|
if m.seq == delay_item_seq: |
|
|
|
self.progress("At delay item") |
|
|
|
at_delay_item = "(delay item)" |
|
|
|
|
|
|
|
self.progress("MISSION_CURRENT.seq=%u %s" % (m.seq, at_delay_item)) |
|
|
|
if m.seq > delay_item_seq: |
|
|
|
if m.seq > delay_item_seq: |
|
|
|
if count_stop == -1: |
|
|
|
if count_stop == -1: |
|
|
|
count_stop_m = self.mav.recv_match(type='SYSTEM_TIME', |
|
|
|
count_stop_m = self.mav.recv_match(type='SYSTEM_TIME', |
|
|
@ -2009,24 +1988,11 @@ class AutoTestCopter(AutoTest): |
|
|
|
if error > 2: |
|
|
|
if error > 2: |
|
|
|
raise NotAchievedException("delay outside expectations") |
|
|
|
raise NotAchievedException("delay outside expectations") |
|
|
|
|
|
|
|
|
|
|
|
except Exception as e: |
|
|
|
|
|
|
|
self.progress("Exception caught") |
|
|
|
|
|
|
|
ex = e |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
self.zero_throttle() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if ex is not None: |
|
|
|
|
|
|
|
raise ex |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def fly_nav_takeoff_delay_abstime(self): |
|
|
|
def fly_nav_takeoff_delay_abstime(self): |
|
|
|
"""make sure taking off at a specific time works""" |
|
|
|
"""make sure taking off at a specific time works""" |
|
|
|
self.load_mission("copter_nav_delay_takeoff.txt") |
|
|
|
self.load_mission("copter_nav_delay_takeoff.txt") |
|
|
|
|
|
|
|
|
|
|
|
self.progress("Starting mission") |
|
|
|
self.change_mode("LOITER") |
|
|
|
|
|
|
|
|
|
|
|
self.mavproxy.send('mode loiter\n') # stabilize mode |
|
|
|
|
|
|
|
self.wait_heartbeat() |
|
|
|
|
|
|
|
self.wait_mode('LOITER') |
|
|
|
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
|
|
|
|
|
|
|
delay_item_seq = 2 |
|
|
|
delay_item_seq = 2 |
|
|
@ -2034,13 +2000,9 @@ class AutoTestCopter(AutoTest): |
|
|
|
delay_for_seconds = 77 |
|
|
|
delay_for_seconds = 77 |
|
|
|
reset_at = self.get_sim_time_cached() |
|
|
|
reset_at = self.get_sim_time_cached() |
|
|
|
|
|
|
|
|
|
|
|
self.context_push() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
ex = None |
|
|
|
|
|
|
|
try: |
|
|
|
|
|
|
|
self.arm_vehicle() |
|
|
|
self.arm_vehicle() |
|
|
|
self.mavproxy.send('mode auto\n') # stabilize mode |
|
|
|
self.change_mode("AUTO") |
|
|
|
self.wait_mode('AUTO') |
|
|
|
|
|
|
|
self.set_rc(3, 1600) |
|
|
|
self.set_rc(3, 1600) |
|
|
|
|
|
|
|
|
|
|
|
# should not take off for about least 77 seconds |
|
|
|
# should not take off for about least 77 seconds |
|
|
@ -2067,15 +2029,6 @@ class AutoTestCopter(AutoTest): |
|
|
|
if not took_off: |
|
|
|
if not took_off: |
|
|
|
raise NotAchievedException("Did not take off") |
|
|
|
raise NotAchievedException("Did not take off") |
|
|
|
|
|
|
|
|
|
|
|
except Exception as e: |
|
|
|
|
|
|
|
self.progress("Exception caught") |
|
|
|
|
|
|
|
ex = e |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
self.zero_throttle() |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if ex is not None: |
|
|
|
|
|
|
|
raise ex |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def test_setting_modes_via_modeswitch(self): |
|
|
|
def test_setting_modes_via_modeswitch(self): |
|
|
|
self.context_push() |
|
|
|
self.context_push() |
|
|
|
ex = None |
|
|
|
ex = None |
|
|
|