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

AC_AutoTune: make safe shutdown for tradheli when landing in Autotune #27423

Merged
merged 2 commits into from
Jul 3, 2024

Conversation

bnsgeyer
Copy link
Contributor

This PR fixes a bug in autotune that was documented in issue #27418. A tradheli user discovered this bug after landing in autotune and as the aircraft rotor system was spooling down, accidentally raised the collective, commanding positive climb rate. This caused the motor interlock to engage unintentionally and caused the main gear to be stripped. This would not usually happen in this case but did because of a bad setting for H_RSC_IDLE. Regardless, this illustrates the possibility for the rotor to spool up once landed.

The fix to this bug is to change the logic so the interlock can never be enabled after landing in autotune. In fact this PR causes the aircraft to disarm once ground idle is reached. So this will affect the behavior for multirotors too. @lthall I wasn't sure what the original intention of keeping the aircraft from disarming after the user lands in autotune as well as allowing the spool state to go throttle unlimited if the user commands a climb rate.

@@ -38,30 +38,20 @@ void AutoTune::run()
// apply SIMPLE mode transform to pilot inputs
copter.update_simple_mode();

// reset target lean angles and heading while landed
// disarm when the landing detector says we've landed and spool state is ground idle
Copy link
Contributor

@rmackay9 rmackay9 Jun 30, 2024

Choose a reason for hiding this comment

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

disarming when the vehicle becomes landed is available as a flight option (or arming option?) but its not the default so I think this would surprise users

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Well, we would never allow the user to takeoff in autotune so why would we leave the aircraft in an armed state after landing. Plus disarming would then save the gains which i think is helpful for the user.

Copy link
Contributor

Choose a reason for hiding this comment

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

I think we don't allow users to arm in autotune but they can takeoff in autotune. It's really more a matter of consistency though. If we want the vehicle to always disarm while landed we can discuss and perhaps make that change but having different modes behave differently is confusing to the user

Copy link
Contributor Author

Choose a reason for hiding this comment

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

There isn’t any logic in autotune to support takeoff.

Copy link
Collaborator

Choose a reason for hiding this comment

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

I tend to agree with @rmackay9 I want disarm to be under my control, not autotune - this would also be a surprise.

Copy link
Contributor

Choose a reason for hiding this comment

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

The alternative is to ignore any positive climb rate or switch out of mot_spin_arm after landed but still let the user disarm.


// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

@rmackay9 I suppose this would allow users to takeoff. however this is far from the current code in althold and loiter used for spool state management and takeoff.

IMHO, I don't think it is a good/safe practice to allow takeoff in autotune. @lthall what do you think?

Copy link
Contributor

Choose a reason for hiding this comment

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

The first twitch of autotune can be very large and aggressive. If we let people take-off in autotune and they hover at 1m for a second that first twitch could easily cause a crash.

Given we switch to Autotune from Loiter or Alt_Hold to determine what behaviour we use I don't think we should be starting in Autotune.

Copy link
Contributor

Choose a reason for hiding this comment

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

In case it matters, I think this is an existing issue

@lthall
Copy link
Contributor

lthall commented Jul 1, 2024

Autotune does not support take-off because it can twitch at any time. To support take-off we would need to only take-off if autotune has completed.

I don't think shutting down as soon as we land will surprise people given that people have just been watching potentially crash inducing pitch and roll changes. In general I think people would be happy to see the aircraft shut down quickly once on the ground. I can't imagine that people are deliberately doing touch and go's just after autotune.

Don't Auto modes automatically shut down once landed, even if they are not intended to land? I am thinking of Autotune more of an automated mode than a manual mode. So I am not too concerned that it shuts down automatically like an auto mode.

@bnsgeyer bnsgeyer force-pushed the pr-autotune-spool-fix branch from 668b15c to 6f69a6b Compare July 2, 2024 03:01
@bnsgeyer bnsgeyer force-pushed the pr-autotune-spool-fix branch from 6f69a6b to 27af7c9 Compare July 2, 2024 03:08
Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

Looks good.

@rmackay9
Copy link
Contributor

rmackay9 commented Jul 3, 2024

@bnsgeyer, feel free to merge when you like

@bnsgeyer
Copy link
Contributor Author

bnsgeyer commented Jul 3, 2024

@rmackay9 @lthall is there any desire to back port this to 4.5?

@bnsgeyer bnsgeyer merged commit a346323 into ArduPilot:master Jul 3, 2024
72 checks passed
@rmackay9
Copy link
Contributor

rmackay9 commented Jul 3, 2024

Hi @bnsgeyer,

Because of the change in behaviour I'd personally prefer it waited until 4.6 (which is 2 or 3 months from starting beta testing) but if we think it is a real hazard then we could backport it.

@bnsgeyer
Copy link
Contributor Author

bnsgeyer commented Jul 4, 2024

@rmackay9 No. I think that is fine. This latest event was a problem because the user a wrong setting which caused a rapid acceleration of the motor and stripped his main gear. In most cases, the user would realize that the engine is starting again (which would be a slow acceleration) and disable motor interlock on their transmitter.

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

Successfully merging this pull request may close these issues.

5 participants