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

Expand tradheli inverted flight to non manual throttle modes #26435

Merged
merged 8 commits into from
Jul 1, 2024

Conversation

bnsgeyer
Copy link
Contributor

@bnsgeyer bnsgeyer commented Mar 7, 2024

The fix was a little simpler than I thought. It looks like a change to the handling of landing collective is what broke the ability to use inverted flight in non-manual throttle modes. Landing collective is how the collective is kept from going below the minimum allowable collective when landed. this is managed using the dynamic flight flag as a last resort to keep the collective from being lowered below the minimum allowed in non manual throttle modes.

This wasn't the only thing that need fixed for being able to do inverted flight in loiter and auto modes. The input_thrust_vector... methods needed to be modified to accommodate inverted flight. This was a bit of a hack on my part and will need help from @lthall or @IamPete1 to make sure these are right.

Additional modes can be added now. I just put althold, loiter, and auto modes in as a first cut. This has only been tested in real flight simulator

@bnsgeyer bnsgeyer added TradHeli WikiNeeded needs wiki update labels Mar 7, 2024
@bnsgeyer bnsgeyer requested review from lthall and IamPete1 March 7, 2024 04:35
@bnsgeyer bnsgeyer self-assigned this Mar 7, 2024
@tridge
Copy link
Contributor

tridge commented Mar 7, 2024

@bnsgeyer thanks!

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

Missing a state reset on mode change. Although I would like to see this ask attitude control rather than keeping two copys of the same state.

Allowing inverted in auto makes me nervous because I don't think we have a full set attitude control input functions that apply the inversion? So it might mostly work and then crash on a unusual waypoint that uses a different input command.

The change to should_use_landing_swash means that motors will now set get_below_land_min_coll will return true which means landing might be detected? It seems reasonable to disable landing detection if inverted?

ArduCopter/Copter.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h Outdated Show resolved Hide resolved
@bnsgeyer
Copy link
Contributor Author

bnsgeyer commented Mar 7, 2024

The change to should_use_landing_swash means that motors will now set get_below_land_min_coll will return true which means landing might be detected? It seems reasonable to disable landing detection if inverted?

@IamPete1 i have already guarded against this in the landing detector. open to a different way if you don’t think this is the right approach.

https://github.com/bnsgeyer/ardupilot/blob/master/ArduCopter/land_detector.cpp#L77

@IamPete1
Copy link
Member

IamPete1 commented Mar 7, 2024

@IamPete1 i have already guarded against this in the landing detector. open to a different way if you don’t think this is the right approach.

https://github.com/bnsgeyer/ardupilot/blob/master/ArduCopter/land_detector.cpp#L77

Ah, I see, it checks roll angle rather than the inverted flag. That is just in manual throttle modes? I think we would need to expand that check to all modes.

@bnsgeyer
Copy link
Contributor Author

bnsgeyer commented Mar 8, 2024

Ah, I see, it checks roll angle rather than the inverted flag. That is just in manual throttle modes? I think we would need to expand that check to all modes.

I believe this is what covers all non-manual throttle modes. I think @lthall helped me with this a while back.
https://github.com/bnsgeyer/ardupilot/blob/master/ArduCopter/land_detector.cpp#L81

Allowing inverted in auto makes me nervous because I don't think we have a full set attitude control input functions that apply the inversion? So it might mostly work and then crash on a unusual waypoint that uses a different input command.

We will have to discuss this during the devcall. My impression when this first went in (i wasn't the author) was that there was some testing done but this was more to provide something fun for users. We weren't going to go through extensive coding to ensure it is flawless in all modes. I don't know the right answer here. we could let it go in but provide pretty stern warnings in the wiki that it is experimental. The other thing i see with the auto modes or any mode that requires GPS is that the GPS will eventually lose the fix, at least that is what I would think if it is facing the ground instead of the sky.

@IamPete1
Copy link
Member

IamPete1 commented Mar 8, 2024

I believe this is what covers all non-manual throttle modes. I think @lthall helped me with this a while back.
https://github.com/bnsgeyer/ardupilot/blob/master/ArduCopter/land_detector.cpp#L81

Right, I think we just need to tack on a !attitude_control->get_inverted_flight() because in this case motors->limit.throttle_lower is really the upper limit for max thrust.

@tridge
Copy link
Contributor

tridge commented Mar 11, 2024

The other thing i see with the auto modes or any mode that requires GPS is that the GPS will eventually lose the fix, at least that is what I would think if it is facing the ground instead of the sky.

i've done inverted in planes doing multiple full circuits without issues. Once you have lock then losing it is unlikely. It will become less accurate, but unlikely to lose it completely

@tridge
Copy link
Contributor

tridge commented Mar 11, 2024

I've tested this in AUTO in RealFlight with the raptor 720 heli and it works fine. It also works in GUIDED if enabled in mode.h

@bnsgeyer
Copy link
Contributor Author

Notes from devcall:
Future PR to address inadvertent switch to loiter while inverted and have the collective go zero pitch or help keep from losing altitude while rolling out.

Add force flying to the inverted feature to keep landing detector from inadvertently declaring landed.

@bnsgeyer bnsgeyer force-pushed the pr-inverted branch 2 times, most recently from 2781a19 to 13841b2 Compare March 15, 2024 23:29
@bnsgeyer bnsgeyer requested a review from IamPete1 March 16, 2024 00:47
@bnsgeyer bnsgeyer force-pushed the pr-inverted branch 2 times, most recently from 5efdb3c to 9cc494b Compare March 22, 2024 00:46
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

I plotted the boost (red) and inverted (blue) factors.

image

When multiplied we get:
image

That assumes target and desired angle are equal of course, but it seems like a sensible function to use.

ArduCopter/mode_stabilize_heli.cpp Outdated Show resolved Hide resolved
ArduCopter/land_detector.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h Outdated Show resolved Hide resolved
libraries/AP_Motors/AP_MotorsHeli.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp Outdated Show resolved Hide resolved
bnsgeyer and others added 3 commits May 22, 2024 22:08
Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

LGTM

@bnsgeyer
Copy link
Contributor Author

bnsgeyer commented Jul 1, 2024

This was tested by @Ferruccio1984 on an actual heli and it worked well. There was some heading changes during the roll inverted but it seems like that is the actual heading changing and pulling the target heading with it. I will put some pretty stern warnings about this feature in general as it hasn't been extensively tested. The important thing though is that it loses very little altitude in the transition to inverted and back (<5m)

@rmackay9 rmackay9 merged commit c5585f8 into ArduPilot:master Jul 1, 2024
91 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
TradHeli WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

5 participants