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
879d4474
Commit
879d4474
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Parachute: alt_min units to meters
parent
50df9531
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
libraries/AP_Parachute/AP_Parachute.cpp
+4
-4
4 additions, 4 deletions
libraries/AP_Parachute/AP_Parachute.cpp
libraries/AP_Parachute/AP_Parachute.h
+4
-4
4 additions, 4 deletions
libraries/AP_Parachute/AP_Parachute.h
with
8 additions
and
8 deletions
libraries/AP_Parachute/AP_Parachute.cpp
+
4
−
4
View file @
879d4474
...
...
@@ -46,11 +46,11 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] PROGMEM = {
// @Param: ALT_MIN
// @DisplayName: Parachute min altitude in cm above home
// @Description: Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
// @Range: 0
10
000
// @Units:
Centim
eters
// @Increment: 1
00
// @Range: 0
32
000
// @Units:
M
eters
// @Increment: 1
// @User: Standard
AP_GROUPINFO
(
"ALT_MIN"
,
4
,
AP_Parachute
,
_alt_min
_cm
,
AP_PARACHUTE_ALT_MIN_DEFAULT
),
AP_GROUPINFO
(
"ALT_MIN"
,
4
,
AP_Parachute
,
_alt_min
,
AP_PARACHUTE_ALT_MIN_DEFAULT
),
AP_GROUPEND
};
...
...
This diff is collapsed.
Click to expand it.
libraries/AP_Parachute/AP_Parachute.h
+
4
−
4
View file @
879d4474
...
...
@@ -22,7 +22,7 @@
#define AP_PARACHUTE_SERVO_ON_PWM_DEFAULT 1300 // default PWM value to move servo to when shutter is activated
#define AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT 1100 // default PWM value to move servo to when shutter is deactivated
#define AP_PARACHUTE_ALT_MIN_DEFAULT 10
00
// default min altitude the vehicle should have before parachute is released
#define AP_PARACHUTE_ALT_MIN_DEFAULT
10
// default min altitude the vehicle should have before parachute is released
/// @class AP_Parachute
/// @brief Class managing the release of a parachute
...
...
@@ -52,9 +52,9 @@ public:
/// update - shuts off the trigger should be called at about 10hz
void
update
();
/// alt_min
_cm
- returns the min altitude above home the vehicle should have before parachute is released
/// alt_min - returns the min altitude above home the vehicle should have before parachute is released
/// 0 = altitude check disabled
int16_t
alt_min
_cm
()
const
{
return
_alt_min
_cm
;
}
int16_t
alt_min
()
const
{
return
_alt_min
;
}
static
const
struct
AP_Param
::
GroupInfo
var_info
[];
...
...
@@ -64,7 +64,7 @@ private:
AP_Int8
_release_type
;
// 0:Servo,1:Relay
AP_Int16
_servo_on_pwm
;
// PWM value to move servo to when shutter is activated
AP_Int16
_servo_off_pwm
;
// PWM value to move servo to when shutter is deactivated
AP_Int16
_alt_min
_cm
;
// min altitude the vehicle should have before parachute is released
AP_Int16
_alt_min
;
// min altitude the vehicle should have before parachute is released
// internal variables
AP_Relay
&
_relay
;
// pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
...
...
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