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

Plane: fixed ramp of motors on back transition in tilt quadplanes #26249

Merged
merged 3 commits into from
Mar 5, 2024

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Feb 18, 2024

this removes the special case for SHUT_DOWN state of the motors in tilt quadplanes. The old code seemed to assume that the output_motor_mask() doesn't work in SHUT_DOWN state, but in fact it does, so we can get proper spoolup behavious on back transition just by removing the special case

this PR builds on #26248 to give us a quadplane-tilt frame for testing

@IamPete1
Copy link
Member

I suspect we could remove the tilt-rotor motors_active concept all together, the only other user is here:

if (motors->get_throttle() > 0.01f || tiltrotor.motors_active()) {

I would like to do the same for tailsitter, then it remove the special case completely. But that can wait for a new PR.

get_desired_spool_state is used quite a lot, so that might give a different result now, but since SLT's don't have a problem I don't think it will be a issue.

@tridge
Copy link
Contributor Author

tridge commented Feb 18, 2024

I suspect we could remove the tilt-rotor motors_active concept all together, the only other user is here:

I think we need to keep that user though, or throttle suppression could break for tilt rotors

@tridge tridge mentioned this pull request Feb 20, 2024
52 tasks
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 had a bit more of a in-depth look. I don't think this will work if slew limits are set (Q_M_SLEW_UP_TIME and Q_M_SLEW_DN_TIME).

The problem is that the output mask method slews the outputs here:

set_actuator_with_slew(_actuator[i], thrust + diff_thrust);

The output to motors method zeros that _actuator value if in SpoolState::SHUT_DOWN:

So we would only ever get a throttle of 1 loops worth of spool up.

I'm fairly sure we actually have the same issue now. Except it will be limited to one loops change from the output values from the mixer that are set in the SpoolState::THROTTLE_UNLIMITED.

The esay fix is just to say that we don't care about spool limits and remove them in the output mask. However, that would result in a very big jump in individual outputs as they swap. It would also be nice for the spool up to come up to meet the slewed actuators rather than them swapping from one method to the other instantly.

Alternately we could add a "has mask override" method that would skip setting the actuator in the shut down case. I suspect that will allow us to get the best result, but it does mean were leaking QP logic into motors a bit. But it might be a nice path have the slew limits applied in motor test for example.

@tridge
Copy link
Contributor Author

tridge commented Feb 21, 2024

Alternately we could add a "has mask override" method that would skip setting the actuator in the shut down case. I suspect that will allow us to get the best result, but it does mean were leaking QP logic into motors a bit. But it might be a nice path have the slew limits applied in motor test for example.

I've implemented that in the PR

@tridge tridge removed the DevCallEU label Feb 21, 2024
@rmackay9
Copy link
Contributor

This looks OK to me, at least it's better than duplicating the ramp up code in the quadplane code.

@tridge
Copy link
Contributor Author

tridge commented Feb 24, 2024

I flew this on a GriffinPro today, no issues

@@ -192,4 +192,14 @@ class AP_MotorsMulticopter : public AP_Motors {

// array of motor output values
float _actuator[AP_MOTORS_MAX_NUM_MOTORS];

/* motor enabled, checking the override mask
_motor_mask_override is only set for tilt quadplanes
Copy link
Member

Choose a reason for hiding this comment

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

Also "copter" tailsitters.

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.

Might want to do the same in ground idle too?

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.

There is a off by one bug in tricopter than means the slewed actuators don't match between mask and normal output.

set_actuator_with_slew(_actuator[1], actuator_spin_up_to_ground_idle());
set_actuator_with_slew(_actuator[2], actuator_spin_up_to_ground_idle());
set_actuator_with_slew(_actuator[4], actuator_spin_up_to_ground_idle());

@IamPete1
Copy link
Member

This is a fix for the tricopter motor indexing thing. #26313

this allows for Q_M_SPOOL_TIME to work correctly for back transition
this fixes tilt quadplanes with slew limits when we set motors state
to SHUT_DOWN
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.

The is a small conflict with the tricopter indexing fixup.

libraries/AP_Motors/AP_MotorsTri.cpp Outdated Show resolved Hide resolved
stop changing motors outside the given mask in output_motor_mask,
which gives smoother ramp down in tilt quadplanes when we are
transitioning to forward flight

thanks to Pete for the suggestion
@tridge tridge merged commit 171da3d into ArduPilot:master Mar 5, 2024
89 checks passed
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.

4 participants