|
|
|
@ -74,7 +74,7 @@ def takeoff(mavproxy, mav, alt_min = 30, takeoff_throttle=1700):
@@ -74,7 +74,7 @@ def takeoff(mavproxy, mav, alt_min = 30, takeoff_throttle=1700):
|
|
|
|
|
return True |
|
|
|
|
|
|
|
|
|
# loiter - fly south west, then hold loiter within 5m position and altitude |
|
|
|
|
def loiter(mavproxy, mav, holdtime=15, maxaltchange=5, maxdistchange=5): |
|
|
|
|
def loiter(mavproxy, mav, holdtime=10, maxaltchange=5, maxdistchange=5): |
|
|
|
|
'''hold loiter position''' |
|
|
|
|
mavproxy.send('switch 5\n') # loiter mode |
|
|
|
|
wait_mode(mav, 'LOITER') |
|
|
|
@ -572,8 +572,8 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=30, max_distance=100):
@@ -572,8 +572,8 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=30, max_distance=100):
|
|
|
|
|
# record position for 30 seconds |
|
|
|
|
while glitch_current < glitch_num: |
|
|
|
|
time_in_sec = int(time.time() - tstart); |
|
|
|
|
if time_in_sec > glitch_current and glitch_current != -1: |
|
|
|
|
glitch_current = time_in_sec |
|
|
|
|
if (time_in_sec * 2) > glitch_current and glitch_current != -1: |
|
|
|
|
glitch_current = (time_in_sec * 2) |
|
|
|
|
# apply next glitch |
|
|
|
|
if glitch_current < glitch_num: |
|
|
|
|
mavproxy.send('param set SIM_GPS_GLITCH_X %.7f\n' % glitch_lat[glitch_current]) |
|
|
|
@ -584,7 +584,17 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=30, max_distance=100):
@@ -584,7 +584,17 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=30, max_distance=100):
|
|
|
|
|
mavproxy.send('param set SIM_GPS_GLITCH_Y 0\n') |
|
|
|
|
|
|
|
|
|
# continue with the mission |
|
|
|
|
ret = wait_waypoint(mav, 0, num_wp, timeout=500, mode='AUTO') |
|
|
|
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO') |
|
|
|
|
|
|
|
|
|
# wait for arrival back home |
|
|
|
|
m = mav.recv_match(type='VFR_HUD', blocking=True) |
|
|
|
|
pos = mav.location() |
|
|
|
|
dist_to_home = get_distance(HOME, pos) |
|
|
|
|
while dist_to_home > 5: |
|
|
|
|
m = mav.recv_match(type='VFR_HUD', blocking=True) |
|
|
|
|
pos = mav.location() |
|
|
|
|
dist_to_home = get_distance(HOME, pos) |
|
|
|
|
print("Dist from home: %u" % dist_to_home) |
|
|
|
|
|
|
|
|
|
# turn off simulator display of gps and actual position |
|
|
|
|
show_gps_and_sim_positions(mavproxy, False) |
|
|
|
@ -740,6 +750,45 @@ def fly_circle(mavproxy, mav, maxaltchange=10, holdtime=36):
@@ -740,6 +750,45 @@ def fly_circle(mavproxy, mav, maxaltchange=10, holdtime=36):
|
|
|
|
|
print("CIRCLE OK for %u seconds" % holdtime) |
|
|
|
|
return True |
|
|
|
|
|
|
|
|
|
# fly_auto_test - fly mission which tests a significant number of commands |
|
|
|
|
def fly_auto_test(mavproxy, mav): |
|
|
|
|
|
|
|
|
|
# Fly mission #1 |
|
|
|
|
print("# Upload copter_glitch_mission") |
|
|
|
|
if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "copter_mission.txt")): |
|
|
|
|
print("upload copter_mission.txt failed") |
|
|
|
|
return False |
|
|
|
|
|
|
|
|
|
# this grabs our mission count |
|
|
|
|
if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "copter_mission.txt")): |
|
|
|
|
print("load copter_mission failed") |
|
|
|
|
return False |
|
|
|
|
|
|
|
|
|
# load the waypoint count |
|
|
|
|
global homeloc |
|
|
|
|
global num_wp |
|
|
|
|
print("test: Fly a mission from 1 to %u" % num_wp) |
|
|
|
|
mavproxy.send('wp set 1\n') |
|
|
|
|
|
|
|
|
|
# switch into AUTO mode and raise throttle |
|
|
|
|
mavproxy.send('switch 4\n') # auto mode |
|
|
|
|
wait_mode(mav, 'AUTO') |
|
|
|
|
mavproxy.send('rc 3 1500\n') |
|
|
|
|
|
|
|
|
|
# fly the mission |
|
|
|
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO') |
|
|
|
|
|
|
|
|
|
# set throttle to minimum |
|
|
|
|
mavproxy.send('rc 3 1000\n') |
|
|
|
|
|
|
|
|
|
# wait for disarm |
|
|
|
|
mav.motors_disarmed_wait() |
|
|
|
|
print("MOTORS DISARMED OK") |
|
|
|
|
|
|
|
|
|
print("Auto mission completed: passed=%s" % ret) |
|
|
|
|
|
|
|
|
|
return ret |
|
|
|
|
|
|
|
|
|
def land(mavproxy, mav, timeout=60): |
|
|
|
|
'''land the quad''' |
|
|
|
|
print("STARTING LANDING") |
|
|
|
@ -1005,9 +1054,9 @@ def fly_ArduCopter(viewerip=None, map=False):
@@ -1005,9 +1054,9 @@ def fly_ArduCopter(viewerip=None, map=False):
|
|
|
|
|
print("takeoff failed") |
|
|
|
|
failed = True |
|
|
|
|
|
|
|
|
|
# Loiter for 15 seconds |
|
|
|
|
# Loiter for 10 seconds |
|
|
|
|
print("#") |
|
|
|
|
print("########## Test Loiter for 15 seconds ##########") |
|
|
|
|
print("########## Test Loiter for 10 seconds ##########") |
|
|
|
|
print("#") |
|
|
|
|
if not loiter(mavproxy, mav): |
|
|
|
|
print("loiter failed") |
|
|
|
@ -1015,9 +1064,9 @@ def fly_ArduCopter(viewerip=None, map=False):
@@ -1015,9 +1064,9 @@ def fly_ArduCopter(viewerip=None, map=False):
|
|
|
|
|
|
|
|
|
|
# Loiter Climb |
|
|
|
|
print("#") |
|
|
|
|
print("# Loiter - climb to 40m") |
|
|
|
|
print("# Loiter - climb to 30m") |
|
|
|
|
print("#") |
|
|
|
|
if not change_alt(mavproxy, mav, 40): |
|
|
|
|
if not change_alt(mavproxy, mav, 30): |
|
|
|
|
print("change_alt failed") |
|
|
|
|
failed = True |
|
|
|
|
|
|
|
|
@ -1099,30 +1148,12 @@ def fly_ArduCopter(viewerip=None, map=False):
@@ -1099,30 +1148,12 @@ def fly_ArduCopter(viewerip=None, map=False):
|
|
|
|
|
print("RTL failed") |
|
|
|
|
failed = True |
|
|
|
|
|
|
|
|
|
# Fly mission #1 |
|
|
|
|
print("# Upload copter_mission") |
|
|
|
|
if not upload_mission_from_file(mavproxy, mav, os.path.join(testdir, "copter_mission.txt")): |
|
|
|
|
print("upload_mission_from_file failed") |
|
|
|
|
failed = True |
|
|
|
|
|
|
|
|
|
# this grabs our mission count |
|
|
|
|
print("# store copter_mission locally") |
|
|
|
|
if not load_mission_from_file(mavproxy, mav, os.path.join(testdir, "copter_mission.txt")): |
|
|
|
|
print("load_mission_from_file failed") |
|
|
|
|
failed = True |
|
|
|
|
|
|
|
|
|
print("# Fly mission 1") |
|
|
|
|
if not fly_mission(mavproxy, mav,height_accuracy = 0.5, target_altitude=10): |
|
|
|
|
print("# Fly copter mission") |
|
|
|
|
if not fly_auto_test(mavproxy, mav): |
|
|
|
|
print("fly_mission failed") |
|
|
|
|
failed = True |
|
|
|
|
else: |
|
|
|
|
print("Flew mission 1 OK") |
|
|
|
|
|
|
|
|
|
#mission includes LAND at end so should be ok to disamr |
|
|
|
|
print("# disarm motors") |
|
|
|
|
if not disarm_motors(mavproxy, mav): |
|
|
|
|
print("disarm_motors failed") |
|
|
|
|
failed = True |
|
|
|
|
print("Flew copter mission OK") |
|
|
|
|
|
|
|
|
|
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/ArduCopter-log.bin")): |
|
|
|
|
print("Failed log download") |
|
|
|
|