mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Parachute: added CHUTE_DELAY_MS parameter
on fixed wing it may take quite some time for the propeller to stop
This commit is contained in:
parent
2806171839
commit
894e07a0bd
@ -52,6 +52,15 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ALT_MIN", 4, AP_Parachute, _alt_min, AP_PARACHUTE_ALT_MIN_DEFAULT),
|
AP_GROUPINFO("ALT_MIN", 4, AP_Parachute, _alt_min, AP_PARACHUTE_ALT_MIN_DEFAULT),
|
||||||
|
|
||||||
|
// @Param: DELAY_MS
|
||||||
|
// @DisplayName: Parachute release delay
|
||||||
|
// @Description: Delay in millseconds between motor stop and chute release
|
||||||
|
// @Range: 0 5000
|
||||||
|
// @Units: Milliseconds
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("DELAY_MS", 5, AP_Parachute, _delay_ms, AP_PARACHUTE_RELEASE_DELAY_MS),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -91,10 +100,11 @@ void AP_Parachute::update()
|
|||||||
|
|
||||||
// calc time since release
|
// calc time since release
|
||||||
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
||||||
|
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
|
||||||
|
|
||||||
// check if we should release parachute
|
// check if we should release parachute
|
||||||
if ((_release_time != 0) && !_release_in_progress) {
|
if ((_release_time != 0) && !_release_in_progress) {
|
||||||
if (time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS) {
|
if (time_diff >= delay_ms) {
|
||||||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||||
// move servo
|
// move servo
|
||||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_on_pwm);
|
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_on_pwm);
|
||||||
@ -105,7 +115,7 @@ void AP_Parachute::update()
|
|||||||
_release_in_progress = true;
|
_release_in_progress = true;
|
||||||
_released = true;
|
_released = true;
|
||||||
}
|
}
|
||||||
}else if ((_release_time == 0) || time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
}else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
||||||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||||
// move servo back to off position
|
// move servo back to off position
|
||||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_off_pwm);
|
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_off_pwm);
|
||||||
|
@ -66,6 +66,7 @@ private:
|
|||||||
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; // min altitude the vehicle should have before parachute is released
|
AP_Int16 _alt_min; // min altitude the vehicle should have before parachute is released
|
||||||
|
AP_Int16 _delay_ms; // delay before chute release for motors to stop
|
||||||
|
|
||||||
// internal variables
|
// internal variables
|
||||||
AP_Relay &_relay; // pointer to relay object from the base class Relay.
|
AP_Relay &_relay; // pointer to relay object from the base class Relay.
|
||||||
|
Loading…
Reference in New Issue
Block a user