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
9169fe2b
Commit
9169fe2b
authored
13 years ago
by
Jason Short
Browse files
Options
Downloads
Patches
Plain Diff
AP TEST fixes for new throttle control
parent
b4ee111c
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
+13
-9
13 additions, 9 deletions
Tools/autotest/arducopter.py
with
13 additions
and
9 deletions
Tools/autotest/arducopter.py
+
13
−
9
View file @
9169fe2b
...
@@ -14,6 +14,10 @@ HOME=location(-35.362938,149.165085,584,270)
...
@@ -14,6 +14,10 @@ HOME=location(-35.362938,149.165085,584,270)
homeloc
=
None
homeloc
=
None
num_wp
=
0
num_wp
=
0
def
hover
(
mavproxy
,
mav
):
mavproxy
.
send
(
'
rc 3 1385
\n
'
)
return
True
def
calibrate_level
(
mavproxy
,
mav
):
def
calibrate_level
(
mavproxy
,
mav
):
'''
init the accelerometers
'''
'''
init the accelerometers
'''
print
(
"
Initialising accelerometers
"
)
print
(
"
Initialising accelerometers
"
)
...
@@ -54,7 +58,7 @@ def takeoff(mavproxy, mav, alt_min = 30):
...
@@ -54,7 +58,7 @@ def takeoff(mavproxy, mav, alt_min = 30):
m
=
mav
.
recv_match
(
type
=
'
VFR_HUD
'
,
blocking
=
True
)
m
=
mav
.
recv_match
(
type
=
'
VFR_HUD
'
,
blocking
=
True
)
if
(
m
.
alt
<
alt_min
):
if
(
m
.
alt
<
alt_min
):
wait_altitude
(
mav
,
alt_min
,
(
alt_min
+
5
))
wait_altitude
(
mav
,
alt_min
,
(
alt_min
+
5
))
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
print
(
"
TAKEOFF COMPLETE
"
)
print
(
"
TAKEOFF COMPLETE
"
)
return
True
return
True
...
@@ -86,13 +90,13 @@ def change_alt(mavproxy, mav, alt_min):
...
@@ -86,13 +90,13 @@ def change_alt(mavproxy, mav, alt_min):
m
=
mav
.
recv_match
(
type
=
'
VFR_HUD
'
,
blocking
=
True
)
m
=
mav
.
recv_match
(
type
=
'
VFR_HUD
'
,
blocking
=
True
)
if
(
m
.
alt
<
alt_min
):
if
(
m
.
alt
<
alt_min
):
print
(
"
Rise to alt:%u from %u
"
%
(
alt_min
,
m
.
alt
))
print
(
"
Rise to alt:%u from %u
"
%
(
alt_min
,
m
.
alt
))
mavproxy
.
send
(
'
rc 3 1
80
0
\n
'
)
mavproxy
.
send
(
'
rc 3 1
92
0
\n
'
)
wait_altitude
(
mav
,
alt_min
,
(
alt_min
+
5
))
wait_altitude
(
mav
,
alt_min
,
(
alt_min
+
5
))
else
:
else
:
print
(
"
Lower to alt:%u from %u
"
%
(
alt_min
,
m
.
alt
))
print
(
"
Lower to alt:%u from %u
"
%
(
alt_min
,
m
.
alt
))
mavproxy
.
send
(
'
rc 3 1
07
0
\n
'
)
mavproxy
.
send
(
'
rc 3 1
12
0
\n
'
)
wait_altitude
(
mav
,
(
alt_min
-
5
),
alt_min
)
wait_altitude
(
mav
,
(
alt_min
-
5
),
alt_min
)
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
return
True
return
True
...
@@ -107,7 +111,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
...
@@ -107,7 +111,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
save_wp
(
mavproxy
,
mav
)
save_wp
(
mavproxy
,
mav
)
print
(
"
turn
"
)
print
(
"
turn
"
)
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
mavproxy
.
send
(
'
rc 4 1610
\n
'
)
mavproxy
.
send
(
'
rc 4 1610
\n
'
)
if
not
wait_heading
(
mav
,
0
):
if
not
wait_heading
(
mav
,
0
):
return
False
return
False
...
@@ -156,7 +160,7 @@ def fly_RTL(mavproxy, mav, side=60):
...
@@ -156,7 +160,7 @@ def fly_RTL(mavproxy, mav, side=60):
'''
Fly, return, land
'''
'''
Fly, return, land
'''
mavproxy
.
send
(
'
switch 6
\n
'
)
mavproxy
.
send
(
'
switch 6
\n
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
failed
=
False
failed
=
False
print
(
"
# Going forward %u meters
"
%
side
)
print
(
"
# Going forward %u meters
"
%
side
)
...
@@ -181,7 +185,7 @@ def fly_failsafe(mavproxy, mav, side=60):
...
@@ -181,7 +185,7 @@ def fly_failsafe(mavproxy, mav, side=60):
'''
Fly, Failsafe, return, land
'''
'''
Fly, Failsafe, return, land
'''
mavproxy
.
send
(
'
switch 6
\n
'
)
mavproxy
.
send
(
'
switch 6
\n
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
failed
=
False
failed
=
False
print
(
"
# Going forward %u meters
"
%
side
)
print
(
"
# Going forward %u meters
"
%
side
)
...
@@ -210,7 +214,7 @@ def fly_simple(mavproxy, mav, side=60, timeout=120):
...
@@ -210,7 +214,7 @@ def fly_simple(mavproxy, mav, side=60, timeout=120):
'''
fly Simple, flying N then E
'''
'''
fly Simple, flying N then E
'''
mavproxy
.
send
(
'
switch 6
\n
'
)
mavproxy
.
send
(
'
switch 6
\n
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
wait_mode
(
mav
,
'
STABILIZE
'
)
mavproxy
.
send
(
'
rc 3 1440
\n
'
)
hover
(
mavproxy
,
mav
)
tstart
=
time
.
time
()
tstart
=
time
.
time
()
failed
=
False
failed
=
False
...
@@ -236,7 +240,7 @@ def fly_simple(mavproxy, mav, side=60, timeout=120):
...
@@ -236,7 +240,7 @@ def fly_simple(mavproxy, mav, side=60, timeout=120):
mavproxy
.
send
(
'
rc 2 1500
\n
'
)
mavproxy
.
send
(
'
rc 2 1500
\n
'
)
#restore to default
#restore to default
mavproxy
.
send
(
'
param set SIMPLE 0
\n
'
)
mavproxy
.
send
(
'
param set SIMPLE 0
\n
'
)
mavproxy
.
send
(
'
rc 3 1430
\n
'
)
hover
(
mavproxy
,
mav
)
return
not
failed
return
not
failed
...
...
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