Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
028b7d1c
Commit
028b7d1c
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
AutoTest: fix AVC copter test
Also incorporate file name changes
parent
5c7cbc6e
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
Tools/autotest/arducopter.py
+46
-30
46 additions, 30 deletions
Tools/autotest/arducopter.py
with
46 additions
and
30 deletions
Tools/autotest/arducopter.py
+
46
−
30
View file @
028b7d1c
...
@@ -789,6 +789,45 @@ def fly_auto_test(mavproxy, mav):
...
@@ -789,6 +789,45 @@ def fly_auto_test(mavproxy, mav):
return
ret
return
ret
# fly_avc_test - fly AVC mission
def
fly_avc_test
(
mavproxy
,
mav
):
# upload mission from file
print
(
"
# Upload copter_glitch_mission
"
)
if
not
upload_mission_from_file
(
mavproxy
,
mav
,
os
.
path
.
join
(
testdir
,
"
copter_AVC2013_mission.txt
"
)):
print
(
"
upload copter_mission.txt failed
"
)
return
False
# get number of commands in mission
if
not
load_mission_from_file
(
mavproxy
,
mav
,
os
.
path
.
join
(
testdir
,
"
copter_AVC2013_mission.txt
"
)):
print
(
"
load copter_mission failed
"
)
return
False
# load the waypoint count
global
homeloc
global
num_wp
print
(
"
Fly AVC 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
(
"
AVC mission completed: passed=%s
"
%
ret
)
return
ret
def
land
(
mavproxy
,
mav
,
timeout
=
60
):
def
land
(
mavproxy
,
mav
,
timeout
=
60
):
'''
land the quad
'''
'''
land the quad
'''
print
(
"
STARTING LANDING
"
)
print
(
"
STARTING LANDING
"
)
...
@@ -871,7 +910,7 @@ def fly_ArduCopter(viewerip=None, map=False):
...
@@ -871,7 +910,7 @@ def fly_ArduCopter(viewerip=None, map=False):
mavproxy
.
expect
(
'
Received [0-9]+ parameters
'
)
mavproxy
.
expect
(
'
Received [0-9]+ parameters
'
)
# setup test parameters
# setup test parameters
mavproxy
.
send
(
"
param load %s/
ArduCopter
.parm
\n
"
%
testdir
)
mavproxy
.
send
(
"
param load %s/
copter_params
.parm
\n
"
%
testdir
)
mavproxy
.
expect
(
'
Loaded [0-9]+ parameters
'
)
mavproxy
.
expect
(
'
Loaded [0-9]+ parameters
'
)
# reboot with new parameters
# reboot with new parameters
...
@@ -1195,7 +1234,7 @@ def fly_CopterAVC(viewerip=None, map=False):
...
@@ -1195,7 +1234,7 @@ def fly_CopterAVC(viewerip=None, map=False):
mavproxy
.
expect
(
'
Received [0-9]+ parameters
'
)
mavproxy
.
expect
(
'
Received [0-9]+ parameters
'
)
# setup test parameters
# setup test parameters
mavproxy
.
send
(
"
param load %s/
C
opterAVC.parm
\n
"
%
testdir
)
mavproxy
.
send
(
"
param load %s/
c
opter
_
AVC
2013_params
.parm
\n
"
%
testdir
)
mavproxy
.
expect
(
'
Loaded [0-9]+ parameters
'
)
mavproxy
.
expect
(
'
Loaded [0-9]+ parameters
'
)
# reboot with new parameters
# reboot with new parameters
...
@@ -1266,37 +1305,14 @@ def fly_CopterAVC(viewerip=None, map=False):
...
@@ -1266,37 +1305,14 @@ def fly_CopterAVC(viewerip=None, map=False):
print
(
"
arm_motors failed
"
)
print
(
"
arm_motors failed
"
)
failed
=
True
failed
=
True
# Fly mission #1
print
(
"
# Fly AVC mission
"
)
print
(
"
# Upload AVC mission
"
)
if
not
fly_avc_test
(
mavproxy
,
mav
):
if
not
upload_mission_from_file
(
mavproxy
,
mav
,
os
.
path
.
join
(
testdir
,
"
AVC2013.txt
"
)):
print
(
"
fly_avc_test failed
"
)
print
(
"
upload_mission_from_file failed
"
)
failed
=
True
# this grabs our mission count
print
(
"
# store mission1 locally
"
)
if
not
load_mission_from_file
(
mavproxy
,
mav
,
os
.
path
.
join
(
testdir
,
"
AVC2013.txt
"
)):
print
(
"
load_mission_from_file failed
"
)
failed
=
True
print
(
"
# raising throttle
"
)
mavproxy
.
send
(
'
rc 3 1300
\n
'
)
print
(
"
# Fly mission 1
"
)
if
not
fly_mission
(
mavproxy
,
mav
,
height_accuracy
=
0.5
,
target_altitude
=
10
):
print
(
"
fly_mission failed
"
)
failed
=
True
failed
=
True
else
:
else
:
print
(
"
Flew mission 1 OK
"
)
print
(
"
Flew AVC mission OK
"
)
print
(
"
# lowering throttle
"
)
mavproxy
.
send
(
'
rc 3 1000
\n
'
)
#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
#mission includes disarm at end so should be ok to download logs now
if
not
log_download
(
mavproxy
,
mav
,
util
.
reltopdir
(
"
../buildlogs/CopterAVC-log.bin
"
)):
if
not
log_download
(
mavproxy
,
mav
,
util
.
reltopdir
(
"
../buildlogs/CopterAVC-log.bin
"
)):
print
(
"
Failed log download
"
)
print
(
"
Failed log download
"
)
failed
=
True
failed
=
True
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment