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
01e5ae6e
Commit
01e5ae6e
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Copter: integrate parachute alt_min units change
parent
879d4474
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/crash_check.pde
+3
-3
3 additions, 3 deletions
ArduCopter/crash_check.pde
with
3 additions
and
3 deletions
ArduCopter/crash_check.pde
+
3
−
3
View file @
01e5ae6e
...
...
@@ -110,7 +110,7 @@ void parachute_check()
}
// ensure the first control_loss event is from above the min altitude
if
(
control_loss_count
==
0
&&
parachute
.
alt_min
_cm
()
!=
0
&&
baro_alt
<
parachute
.
alt_min
_cm
(
))
{
if
(
control_loss_count
==
0
&&
parachute
.
alt_min
()
!=
0
&&
(
baro_alt
<
(
uint32_t
)
parachute
.
alt_min
()
*
100
))
{
return
;
}
...
...
@@ -174,7 +174,7 @@ static void parachute_release()
static
void
parachute_manual_release
()
{
// do not release if we are landed or below the minimum altitude above home
if
(
ap
.
land_complete
||
(
parachute
.
alt_min
_cm
()
!=
0
&&
baro_alt
<
parachute
.
alt_min
_cm
(
)))
{
if
(
ap
.
land_complete
||
(
parachute
.
alt_min
()
!=
0
&&
(
baro_alt
<
(
uint32_t
)
parachute
.
alt_min
()
*
100
)))
{
// warn user of reason for failure
gcs_send_text_P
(
SEVERITY_HIGH
,
PSTR
(
"Parachute: Too Low"
));
// log an error in the dataflash
...
...
@@ -186,4 +186,4 @@ static void parachute_manual_release()
parachute_release
();
}
#endif // PARACHUTE == ENABLED
\ No newline at end of file
#endif // PARACHUTE == ENABLED
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