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

Tradheli: offset collective from landed min when landed in non-manual collective modes #28879

Open
wants to merge 2 commits into
base: master
Choose a base branch
from

Conversation

bnsgeyer
Copy link
Contributor

This PR adds the ability for the user to offset the collective from the landed min collective position when landed in non-manual collective modes. This will enable users to minimize vibrations when landed by being able to have the collective raised after the land complete flag is true.

Copy link
Contributor

@MattKear MattKear left a comment

Choose a reason for hiding this comment

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

Based on my first look at this, I really don't like this feature.

I would like to understand more about the use case. Currently I cannot understand why an operator would want the collective to reduce to land_col_min just to have it raise up again. If someone asked me for this feature my initial reaction would be that they have simply set the landing collective position wrong if it causes undue vibration/loads on when landing in auto-collective modes.

I am fairly sure this introduces a circular dependency. By adding _heliflags.land_complete into these checks where we update the motors limit.throttle_lower and the below_land_min_coll flags. Both of these flags are used in the motor_at_lower_limit check in the landing detector for auto-collective modes. See here:
https://github.com/MattKear/ardupilot/blob/2ce6532698477d7f3e7bc0ae9e18bf9178a94e0e/ArduCopter/land_detector.cpp#L79-L81

If it doesn't actually introduce a circular dependency then it makes it a really tricky piece of code that is hard to maintain to ensure that we don't in the future. (I have been staring at this for a couple of hours now and I can't convince myself definitively either way that the is/isn't a circular dependency).

ArduCopter/heli.cpp Outdated Show resolved Hide resolved
ArduCopter/heli.cpp Outdated Show resolved Hide resolved
@@ -393,7 +402,7 @@ void AP_MotorsHeli::output_logic()
// Servos should exhibit normal flight behavior.

// set limits flags
if (_heliflags.land_complete && !using_leaky_integrator()) {
if ((_heliflags.land_complete || _heliflags.land_complete_maybe) && !using_leaky_integrator()) {
Copy link
Contributor

Choose a reason for hiding this comment

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

I tend to think this should be left as it was (for all spool states). The whole point of having land_complete and land_complete_maybe is to have a two stages to give confidence that the vehicle has landed. land_complete_maybe is more likely to trip as a false positive in flight. It is only limiting I-term though, so I do not have a particularly strong opinion, either way.
I have yet to see a log with a nasty I-term build up between land_complete_maybe and land_complete. @bnsgeyer have you see a case of this, hence this change?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The reason did this was that the original implementation lumped land complete maybe and land complete into the same flag for the motors class. You can see the change where I broke them out so they could be tracked separately. Thus to keep the behavior the same, I had to add the extra conditional here.

@@ -284,13 +284,15 @@ void AP_MotorsHeli_Single::calculate_scalars()
_collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg));

_collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg));
_collective_land_offset_deg.set(constrain_float(_collective_land_offset_deg, _collective_min_deg, _collective_max_deg));
Copy link
Contributor

Choose a reason for hiding this comment

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

I am not a big fan of this pattern in heli, where we are setting the parameter for the users and not telling them. I would much prefer a pre-arm. I appreciate there is a pattern of this already, but I think we should move away from this moving forward. Makes for a better user experience in my view.

libraries/AP_Motors/AP_MotorsHeli_Single.cpp Show resolved Hide resolved
libraries/AP_Motors/AP_MotorsHeli_Single.cpp Outdated Show resolved Hide resolved
libraries/AP_Motors/AP_MotorsHeli_Single.cpp Outdated Show resolved Hide resolved
@@ -388,13 +390,23 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
}

// ensure not below landed/landing collective
if (_heliflags.landing_collective && collective_out < _collective_land_min_pct && !_main_rotor.in_autorotation()) {
if (_heliflags.land_complete && _heliflags.landing_collective && collective_out < _collective_land_min_pct + _collective_offset_landed) {
_collective_offset_landed += 0.0001 * (_collective_land_offset_pct - _collective_offset_landed);
Copy link
Contributor

Choose a reason for hiding this comment

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

Please add a comment to make it clear that this increases collective away from landed collective position.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Dec 16, 2024
@bnsgeyer bnsgeyer force-pushed the pr-landed-coll-offset branch from 8a8a81a to 8e3d2a3 Compare December 20, 2024 04:33
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.

3 participants