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
e6ee50f5
Commit
e6ee50f5
authored
13 years ago
by
Jason Short
Browse files
Options
Downloads
Patches
Plain Diff
Altered the ground detector logic to no continuously run when landed
parent
c45209ea
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduCopter/commands_logic.pde
+11
-8
11 additions, 8 deletions
ArduCopter/commands_logic.pde
with
11 additions
and
8 deletions
ArduCopter/commands_logic.pde
+
11
−
8
View file @
e6ee50f5
...
...
@@ -296,7 +296,7 @@ static void do_approach()
{
// Set a contrained value to EEPROM
g
.
rtl_approach_alt
.
set
(
constrain
((
float
)
g
.
rtl_approach_alt
,
1.0
,
10.0
));
// Get the target_alt in cm
uint16_t
target_alt
=
(
uint16_t
)(
g
.
rtl_approach_alt
*
100
);
...
...
@@ -420,12 +420,13 @@ static bool verify_land_sonar()
// if we are low or don't seem to be decending much, increment ground detector
if
(
current_loc
.
alt
<
40
||
abs
(
climb_rate
)
<
20
)
{
landing_boost
++
;
// reduce the throttle at twice the normal rate
if
(
ground_detector
++
>=
30
)
{
if
(
ground_detector
<
30
)
{
ground_detector
++
}
else
if
(
ground_detector
==
30
){
ground_detector
++
;
land_complete
=
true
;
ground_detector
=
30
;
icount
=
1
;
if
(
g
.
rc_3
.
control_in
==
0
){
// init disarm motors
init_disarm_motors
();
}
return
true
;
...
...
@@ -453,11 +454,13 @@ static bool verify_land_baro()
if
(
current_loc
.
alt
<
150
){
if
(
abs
(
climb_rate
)
<
20
)
{
landing_boost
++
;
if
(
ground_detector
++
>=
30
)
{
if
(
ground_detector
<
30
)
{
ground_detector
++
}
else
if
(
ground_detector
==
30
){
ground_detector
++
;
land_complete
=
true
;
ground_detector
=
30
;
if
(
g
.
rc_3
.
control_in
==
0
){
// init disarm motors
init_disarm_motors
();
}
return
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