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

AP_Motors_Heli: Fix DDFP Min Max Trim Variables #25155

Merged
merged 4 commits into from
Nov 13, 2023

Conversation

MattKear
Copy link
Contributor

Issue found by user on master and reported via Trad Heli channel on discord.

Issues resolved:

  • Servo min, max, trim values were always being retrieved from servo channel 4 not the servo channel assigned to motor 4.
  • The update of the min, max, trim values was only being done in spool state unlimited. So the output was being forced to 0 instead of min until the system is armed and spooled up.

Issues still to resolve:

Testing thus far has been on a bench setup. Board is FMUV3. Signal output is dshot.

@IamPete1
Copy link
Member

IamPete1 commented Oct 1, 2023

My preference here would be to forget about using trim for hover offset, and add a new parameter for that. I'm fairly sure the current implementation messes up the linearisation in anycase. That means we don't need to know then motor endpoints we just do a output_scaled and let the servo library deal with it. We would then add a new param for the hover yaw trim which is added onto the PID output before it gets so far down.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 1, 2023

PR has been reworked as per @IamPete1 suggestion. IMHO this is a cleaner implementation to add the additional parameter for DDFP tail trim. This does require a change to the advice in the Wiki for tuning this parameter. Now users will read the PIDY I term from the hover and insert that value into the new parameter.

I have changed the default linearisation values so that it defaults to linear. As demonstrated by the user PENG on discord, there was some confusion as to why the tail rotor minimum was so high when moving from 4.4 to master. Changing the defaults will prevent user confusion when upgrading versions on existing vehicles.

Tested on the bench:

  • Checked general operation of tail rotor. e.g: Output values with and without interlock. increasing and decreasing yaw rate demand.
  • Checked that H_SV_MAN = passthrough cannot actuate the tail rotor with DDFP.
  • Checked that H_COL2YAW works.
  • Checked that H_DDFP_HOV_TRIM works.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 1, 2023

It may be possible to do a reasonable job of a param conversion from servo trim to a new hover trim value if it is felt that this is neccassary

@MattKear MattKear added the WikiNeeded needs wiki update label Oct 1, 2023
@bnsgeyer
Copy link
Contributor

bnsgeyer commented Oct 2, 2023

@Gone4Dirt and @IamPete1
I appreciate you both jumping in here to fix this.

I'm fairly sure the current implementation messes up the linearisation in anycase. That means we don't need to know then motor endpoints we just do a output_scaled and let the servo library deal with it.

@IamPete1 I don't agree with this. I want to be sure that what you are implying is true. The big thing you have to consider is the collective to yaw compensation. That relies on the thrust being linear. Now maybe I'm misinterpreting what the thrust to output function does but to me it means that I can work in the thrust world and then be able to tell the motor what RPM to spin at the ensure it is a linear thrust profile. The collective to yaw compensation works on the concept that you set the trim of the motor to produce enough tail thrust to offset the drag (torque) of the main rotor at flat pitch and then adds thrust based on collective setting to remove the additional drag(torque) of the main rotor due to the non flat pitch collective setting. This needs to be done in the thrust domain not RPM.

Please consider this and tell me how my implementation is wrong. Not being confrontational, just looking for proof as to why your approach is better.

@bnsgeyer
Copy link
Contributor

bnsgeyer commented Oct 2, 2023

@Ferruccio1984 Just want to tag you on this. I want your input on this as well and we may need to have you test this :)

@Ferruccio1984
Copy link
Contributor

@bnsgeyer ok Bill I'll look this tonight and prepare the heli.

@IamPete1
Copy link
Member

IamPete1 commented Oct 2, 2023

@bnsgeyer The problem is ultimately that the current implementation squashes/stretches the curve around the trim point. It should be moving along the curve not changing it.

To illustrate the issue I have knocked up a quick MATLAB script. There is a plot for each stage of the calculation. First of all using the default thrust linearisation param and servo min/max/trim of 1000/2000/1500.

Yaw input is from the PIDs in the range -1 to 1. The first step is Trim correction. This code (which I think is incorrect):

float servo4_trim = constrain_float((_ddfp_pwm_trim - 1000) / (_ddfp_pwm_max - _ddfp_pwm_min), 0.0f, 1.0f);
if (is_positive(_servo4_out)) {
servo_out = (1.0f - servo4_trim) * _servo4_out + servo4_trim;
} else {
servo_out = servo4_trim * _servo4_out + servo4_trim;
}

With trim in the center this does nothing, its a linear mapping.

image

The thrust_to_actuator call then applys the expo and spin min/max.

rc_write(AP_MOTORS_MOT_4, calculate_ddfp_output(thr_lin.thrust_to_actuator(constrain_float(servo_out, 0.0f, 1.0f))));

image

Finally the calculate_ddfp_output on the same line takes that normalized output and converts it to a PWM.

image

I can then take that PWM, run it backwards through the expo calc to get the linearised thrust. In this case its exactly what we want, linear between 0 and 1.

image

However, if we move that trim point away from the center of min and max this is no longer the case. For the sake of a extreme example this is with a trim of 1200, min and max of 1000 and 2000 as before.

The trim correction in step 1 puts a kink in our line.

image

This kink then propagates through the linearisation, we endup with a PWM output that looks like this:

image

If we then map that back to thrust, you can see were far from the linear thrust output we want.

image

The current implementation of this PR fixis this issue by using the new param to move along the curve rather than changing the curve.

MATLAB code here:
DDFP.zip

@MattKear
Copy link
Contributor Author

MattKear commented Oct 2, 2023

@bnsgeyer to add to Peter's explanation and to come from it at a slightly different way, I have tried to break it down as the diagram below:
image
In the current implementation the trim value, taken from the servo trim parameter, is a throttle that has been converted to an output signal (for arguments sake lets call it a PWM output for simplicity). That trim is considered a "throttle" as it is post linearisation. So you cannot take the servo trim, normalise it using servo min and max, and directly apply that to the yaw out calculation that is pre-linearisation. In that case you are effectively applying a throttle to a thrust.

One fix would be to work the servo trim back through the calculations:

  • Recall that the output when the spool state is "throttle unlimited" is actually between the spin min and spin max range so this needs to be undone and the normalised throttle calculated.
  • The voltage compensation needs to be removed.
  • The inverse of the thrust linearisation then needs to be applied to convert back to thrust from throttle.

The above is do-able just a little messy and unnecessarily complicated IMHO. The alternative to this is the implementation as I have currently presented in this PR. The addition of another parameter which is effectively a trim thrust. This value can be obtained from a flight log with a stable hover, reading off the PIDY.I term from the log. A future improvement could even be to add a trim learn feature that works just like the auto trim does in plane. Where we attempt to minimise yaw I-term by changing the H_DDFP_HOV_TRIM param incrementally.

Something that is now evident to me from this conversation is that I am not correctly applying the limits to the yaw output saturation cases. So in this current implementation we will get I-term wind-up. I will add the limit handling.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 2, 2023

Yaw limiting for DDFP is now implemented.

@MattKear MattKear removed the WIP label Oct 2, 2023
@Ferruccio1984
Copy link
Contributor

Ferruccio1984 commented Oct 2, 2023

I think there is a bit of confusion in regard to servo trim and "hover trim". from reading above it appears that reverting servo trim parameter back through calculations would give the hover trim. Servo trim needs to be set to a low value (my experience between1050-1150us ) to allow safe spool-up and ground operations in general. On top of it of course the PID output and anti-torque feed-forward. Also, "learning" the hover trim is not a safe approach, how would the side wind be taken into account for instance? From the graphs above (graph 6) it appears that when yaw demand goes to -1 pwm output doesn't even reach minimum pwm, which does not correspond to the fw I tested few months ago.

@IamPete1
Copy link
Member

IamPete1 commented Oct 2, 2023

From the graphs above (graph 6) it appears that when yaw demand goes to -1 pwm output doesn't even reach minimum pwm, which does not correspond to the fw I tested few months ago.

This is due to SPIN_MIN.

@bnsgeyer
Copy link
Contributor

bnsgeyer commented Oct 3, 2023

@Gone4Dirt and @IamPete1 Thank you for spending the time to explain your approach. I really appreciate that. Based on Pete's graphs, My approach was working as I anticipated. For a non-centered trim, even though the thrust slope was not the same between inputs greater than trim and less than trim, the thrust output was linear. I would agree that this approach was probably not ideal as the thrust / input changes for left versus right stick inputs. And I think this is probably an issue even with the servo/tailrotor pitch implementation. If you don't have the servo_trim fairly centered then you get asymmetric control for left versus right.

@Gone4Dirt I admit that my use of Servo_trim as the indicator for the center position was a poor choice in this case.

The use of Hover_trim is not the correct term for the trim point. If you are using the collective to yaw compensation then this trim point is the tailrotor pitch to counter torque with rotor flat pitch. if you don't use the collective to yaw compensation then it would be the hover trim tailrotor pitch. This would also be true for DDFP except it is thrust related. I like the idea of using a -1 to 1 parameter to set that center point. and then the line is shifted up and down using the collective to yaw compensation.

@IamPete1
Copy link
Member

IamPete1 commented Oct 3, 2023

And I think this is probably an issue even with the servo/tailrotor pitch implementation. If you don't have the servo_trim fairly centered then you get asymmetric control for left versus right.

I agree, we could add this new yaw trim parameter to with a more generic name so we could apply it to tail servos could swap over to this method in the future, we could do the param conversion from the current servo trim method.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 3, 2023

Agreed, hover trim is not the correct term. I got a bit hung up on the advice here: Setting Tail Trim for the case when we are not considering COL2YAW compensation. I have removed all references to hover from that parameter now.

I have made the parameter name more generic so that the name is not tied to DDFP tails. It could therefore be used for other tail types in the future. However, the implementation in this PR still only allows for use of this parameter in DDFP tails at the moment (param description states this). I want to keep this patch as minimal as possible focussing on fixing DDFP tails for the time being.

Servo trim needs to be set to a low value (my experience between1050-1150us ) to allow safe spool-up and ground operations in general.

I would like to add a throttle ramp tied to the main rotor RSC ramp for DDFP tails. Currently, the motor jumps to the trim value once the interlock is engaged. This behaviour has always be present so I am leaving the ramp change to another PR to keep this one focused on the fix.

@Ferruccio1984
Copy link
Contributor

I would like to add a throttle ramp tied to the main rotor RSC ramp for DDFP tails. Currently, the motor jumps to the trim value once the interlock is engaged. This behaviour has always be present so I am leaving the ramp change to another PR to keep this one focused on the fix.

Yes, totally agree. This is something that should have been there from the very beginning indeed.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 8, 2023

@bnsgeyer is there anything else that needs doing on this PR to get it merged? From my perspective it is ready to go.

@bnsgeyer
Copy link
Contributor

bnsgeyer commented Oct 8, 2023

@Gone4Dirt i would like to hold until @Ferruccio1984 has a chance to flight test it. I will try in the next few days to test it in SITL/realflight with a DDFP model.

@Ferruccio1984
Copy link
Contributor

Ok @bnsgeyer @Gone4Dirt , I should be able to go for a flight test Friday or Saturday. Onboard video and flight log.

@MattKear
Copy link
Contributor Author

MattKear commented Oct 14, 2023

Thanks @Ferruccio1984 for doing that test flight and sending over the video and log file.
@bnsgeyer I have looked over the log file and all looks good to me.
In the flight test, the newly proposed defaults were tested which set the thrust to throttle curve to be linear. Having spoken to @Ferruccio1984 he confirmed that the vehicle flew fine with the same yaw rate tune as was previously attained using the old DDFP control scheme demonstrating that the new param defaults and the linearisation scheme are not a breaking change for people setup. The PIDY log data also demonstrates a good tune.
He did need to set the new H_YAW_TRIM param. We should do something here to either do the param conversion or issue a pre-arm warning (as was done with the H_COL_ANG stuff). What do you think?

@bnsgeyer
Copy link
Contributor

@Gone4Dirt Thanks for looking through the log and talking to @Ferruccio1984 about the test. I will have to think about the param conversion. But the pre-arm warning may be the way to go. Default the trim to 0 for DDFP and the pre-arm checks for it to be zero to determine if the trim has been set

@MattKear
Copy link
Contributor Author

MattKear commented Nov 1, 2023

Param conversion added.
Conversion has been tested on Cube Orange Plus.
The following have been tested:

  • Conversion does nothing if tail type is not configured to be DDFP.
  • Conversion works if tail type is DDFP and the H_YAW_TRIM param has not been previously configured.
  • Conversion does not continue to change H_YAW_TRIM on subsequent reboots once conversion complete.

Note: During testing tail motor output set to channel 6 to prove that the conversion finds motor 4 not servo channel 4.

Copy link
Contributor

@bnsgeyer bnsgeyer left a comment

Choose a reason for hiding this comment

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

@Gone4Dirt I like the param conversion that you implemented. I don't really have an opinion on the internal error comment. Once you and @IamPete1 decide on the way forward, I am happy to put this in.

@MattKear
Copy link
Contributor Author

MattKear commented Nov 3, 2023

@IamPete1 is correct. I have removed the internal error.

@bnsgeyer
Copy link
Contributor

bnsgeyer commented Nov 3, 2023

@Gone4Dirt and @IamPete1 once we are happy with this, do you feel comfortable with me merging it or do you think we need to go back to the devcall?

@Hwurzburg
Copy link
Collaborator

Hwurzburg commented Nov 3, 2023

wiki label needs to remain even if doc draft has been done or will be missed in 4.5 wiki addition work flow

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Nov 3, 2023
@tridge tridge merged commit 2fe100d into ArduPilot:master Nov 13, 2023
86 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

7 participants