Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add: parachute timeout parameter #27500

Draft
wants to merge 5 commits into
base: master
Choose a base branch
from

Conversation

Sztosik
Copy link

@Sztosik Sztosik commented Jul 9, 2024

Replace PARACHUTE_CHECK_TRIGGER_SEC const with CHUTE_TIMEOUT parameter.

The value of PARACHUTE_CHECK_TRIGGER_SEC set to a fixed value may in some cases cause premature parachute deployment.

@@ -104,6 +108,7 @@ class AP_Parachute {
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 _delay_ms; // delay before chute release for motors to stop
AP_Int16 _timeout; // loss of control timeout value in seconds
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If its in seconds I think it should be a float.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have corrected it. What do you think about the range from 0.5 to 5 seconds?

@rmackay9
Copy link
Contributor

rmackay9 commented Jul 9, 2024

This looks pretty good to me. Could you squash the commits together?

@Sztosik Sztosik force-pushed the parachute-check-trigger branch 2 times, most recently from 37a96a7 to fcff383 Compare July 10, 2024 07:48
Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks good to me. @Sztosik could you confirm that you've tested this somehow? I'm pretty sure it does but with such an important subsystem we should be sure. Perhaps set the timeout to a really large number (like 10 seconds) so that it is really obvious that the parameter is having an effect.

@Sztosik
Copy link
Author

Sztosik commented Jul 10, 2024

This looks good to me. @Sztosik could you confirm that you've tested this somehow? I'm pretty sure it does but with such an important subsystem we should be sure. Perhaps set the timeout to a really large number (like 10 seconds) so that it is really obvious that the parameter is having an effect.

I tested it on a Hexsoon EDU450 witch Cube Orange+. I removed the propellers, switched to AltHold mode, armed the drone and raised it, then changed attitudes. Unfortunately, this does not cause the parachute to deploy (I performed an identical test on the stable version and it works fine). Now I'm trying to investigate it.

@IamPete1
Copy link
Member

Unfortunately, this does not cause the parachute to deploy (I performed an identical test on the stable version and it works fine). Now I'm trying to investigate it.

I would guess its the baro altitude check preventing deployment if not falling.

@Sztosik
Copy link
Author

Sztosik commented Jul 10, 2024

I would guess its the baro altitude check preventing deployment if not falling.

I'm not sure, CHUTE_ALT_MIN was set to 1 m and I've rised it to 2 m. Chute was deployed while testing on stable version (Copter 4.5.4) with same configuration.

@Sztosik
Copy link
Author

Sztosik commented Jul 10, 2024

I would guess its the baro altitude check preventing deployment if not falling.

I'm not sure, CHUTE_ALT_MIN was set to 1 m and I've rised it to 2 m. Chute was deployed while testing on stable version (Copter 4.5.4) with same configuration.

Never mind, you have right @IamPete1

@Sztosik
Copy link
Author

Sztosik commented Jul 10, 2024

I tested it on a Hexsoon EDU450 witch Cube Orange+. I removed the propellers, switched to AltHold mode, armed the drone and raised it, then changed attitudes. Unfortunately, this does not cause the parachute to deploy (I performed an identical test on the stable version and it works fine). Now I'm trying to investigate it.

I figured out that value of CRASH_CHECK_TRIGGER_SEC should be always grater than CHUTE_TIMEOUT param. In other case UAV might disarm without deploying parachute.

@Sztosik
Copy link
Author

Sztosik commented Jul 10, 2024

@rmackay9, @IamPete1 I have found another issue that also exist in stable version. In case inability to keep attitude, but without altitude decrease parachute won't be deployed even if vehicle reach CHUTE_CRT_SINK. For now I'm marking this PR as draft and I will try to fix it.

@Sztosik Sztosik marked this pull request as draft July 10, 2024 12:24
@IamPete1
Copy link
Member

@rmackay9, @IamPete1 I have found another issue that also exist in stable version. In case inability to keep attitude, but without altitude decrease parachute won't be deployed even if vehicle reach CHUTE_CRT_SINK. For now I'm marking this PR as draft and I will try to fix it.

I think this time out fix is worth having as it is, you can always come back with the additional changes in a new PR.

@@ -83,6 +83,14 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @User: Standard
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT),

// @Param: TIMEOUT
// @DisplayName: Parachute timeout
// @Description: Triggers the parachute if the loss of control lasts for the time specified by this parameter
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Need to mention that it's copter only.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe we should make the parameters only appear for copter..?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rmackay9 how to achieve it? I've tried with APM_BUILD_COPTER_OR_HELI but automatic checks failed.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jul 10, 2024
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
#if PARACHUTE == ENABLED
// CRASH_CHECK_TRIGGER_SEC should be grater than CHUTE_TIMEOUT, to prevent disarming without deploying parachute
#define CRASH_CHECK_TRIGGER_SEC parachute.get_chute_timeout() + 1.0f
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this define is not doing what you want, as it is used in a multiplication, you need parantheses around the define

    #define CRASH_CHECK_TRIGGER_SEC  (parachute.get_chute_timeout() + 1.0)

@@ -86,7 +92,7 @@ void Copter::crash_check()
// we may be crashing
crash_counter++;

// check if crashing for 2 seconds
// check if crashing for time defined by CRASH_CHECK_TRIGGER_SEC seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the multiply in this line ends up multiplying by 1.0, not the users value

@tridge
Copy link
Contributor

tridge commented Aug 2, 2024

@Sztosik I've pushed fixes for the build issue and multiply to the PR

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

5 participants