mirror of https://github.com/ArduPilot/ardupilot
Parachute: alt_min units to meters
This commit is contained in:
parent
50df95316a
commit
879d447404
|
@ -46,11 +46,11 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] PROGMEM = {
|
||||||
// @Param: ALT_MIN
|
// @Param: ALT_MIN
|
||||||
// @DisplayName: Parachute min altitude in cm above home
|
// @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.
|
// @Description: Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
|
||||||
// @Range: 0 10000
|
// @Range: 0 32000
|
||||||
// @Units: Centimeters
|
// @Units: Meters
|
||||||
// @Increment: 100
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @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
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
|
@ -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_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_SERVO_OFF_PWM_DEFAULT 1100 // default PWM value to move servo to when shutter is deactivated
|
||||||
|
|
||||||
#define AP_PARACHUTE_ALT_MIN_DEFAULT 1000 // 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
|
/// @class AP_Parachute
|
||||||
/// @brief Class managing the release of a 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
|
/// update - shuts off the trigger should be called at about 10hz
|
||||||
void update();
|
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
|
/// 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[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
@ -64,7 +64,7 @@ private:
|
||||||
AP_Int8 _release_type; // 0:Servo,1:Relay
|
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_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 _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
|
// 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
|
AP_Relay& _relay; // pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
|
||||||
|
|
Loading…
Reference in New Issue