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

Fix the correction yaw gives in 2pass (Motor Output Mixer) (Thrust Linearization) #852

Merged
merged 8 commits into from
May 3, 2023

Conversation

Quick-Flash
Copy link
Member

Previously yaw correction would change based on how much roll and pitch was mixed. When mixing an even amount of roll and yaw you would end up with the motors producing more roll than yaw. This problem only even shows up during yaw movements that involve pitch or roll.

example from simulated roll and yaw pidsum with current and new code.

pidsum inputs = 0.2roll, 0.0pitch, 0.2yaw

current code
m1 = -roll+pitch-yaw = 0.09 = -0.03roll+0.03pitch-0.3yaw
m2 = -roll-pitch+yaw = 0.33 = -0.11roll-0.11pitch+0.11yaw
m3 = +roll+pitch+yaw = 0.73 = +0.243roll+0.243pitch+0.243yaw
m4 = +roll-pitch-yaw = 0.49 = +0.163roll-0.163pitch-0.163yaw

roll = -0.03-0.11+0.243+0.163 = 0.266
pitch = 0.03-0.11+0.243-0.163 = 0.0
yaw = -0.03+0.11+0.243-0.163 = 0.16

new code
m1 = -roll+pitch-yaw = 0.01 = -0.003roll+0.003pitch-0.003yaw
m2 = -roll-pitch+yaw = 0.41 = -0.136roll-0.136pitch+0.136yaw
m3 = +roll+pitch+yaw = 0.81 = +0.27roll+0.27pitch+0.27yaw
m4 = +roll-pitch-yaw = 0.41 = +0.136roll-0.136pitch-0.136yaw

roll = -0.003-0.136+0.27+0.136 = 0.267
pitch = +0.003-0.136+0.27-0.136 = 0.0
yaw = -0.003+0.136+0.27-0.136 = 0.267

This code makes sure that yaw will not be shrunk during roll or pitch movements and should improve handling during quick yaw movements.

@nerdCopter nerdCopter added the bug Something isn't working label Aug 4, 2022
@nerdCopter nerdCopter marked this pull request as draft August 4, 2022 14:32
@Quick-Flash Quick-Flash self-assigned this Aug 8, 2022
@Quick-Flash Quick-Flash marked this pull request as ready for review August 8, 2022 22:50
@Quick-Flash
Copy link
Member Author

@tylercorleone perhaps you can find a way to code this more efficiently, but long story short, I found that in 2pass the yaw axis would have less authority during pitch/roll moves. This change gives it the same authority as pitch and roll, but requires a fair bit more logic to make work :(

@nerdCopter nerdCopter removed the bug Something isn't working label Aug 15, 2022
@nerdCopter
Copy link
Member

I flew this and it flew good. submitted logs for review in discord.

Copy link
Member

@nerdCopter nerdCopter left a comment

Choose a reason for hiding this comment

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

  • approved based on conversation
  • will defer to @Quick-Flash to merge or not

@nerdCopter
Copy link
Member

@tylercorleone , are you interested in reviewing this PR? I've flown about 9 packs on it.

@tylercorleone
Copy link
Member

@tylercorleone , are you interested in reviewing this PR? I've flown about 9 packs on it.

Hi guys, honestly lately I lost some interest in quads but above all I've been for so long away that it's hard for me to understand the change.

I would ask only two questions:

  • the current version already has a change compared to what was my initial release. Wasn't that a fix? This one tries to fixes another problem? I already have some difficulties understanding in dept the code after the first fix so it's even more difficult to understand this one
  • the problem here described has been reported by many users? I fear that a fix could mess up the initial idea, and again there's some correlation with the first fix? I don't remember any problem (considering my flight style) with my initial version so it's difficult to me to follow these fixes.

I'll try to look again at this PR anyway.
I'm sorry to not be that helpful 🙁

@Quick-Flash
Copy link
Member Author

@tylercorleone , are you interested in reviewing this PR? I've flown about 9 packs on it.

Hi guys, honestly lately I lost some interest in quads but above all I've been for so long away that it's hard for me to understand the change.

I would ask only two questions:

* the current version already has a change compared to what was my initial release. Wasn't that a fix? This one tries to fixes another problem? I already have some difficulties understanding in dept the code after the first fix so it's even more difficult to understand this one

* the problem here described has been reported by many users? I fear that a fix could mess up the initial idea, and again there's some correlation with the first fix? I don't remember any problem (considering my flight style) with my initial version so it's difficult to me to follow these fixes.

I'll try to look again at this PR anyway. I'm sorry to not be that helpful 🙁

So the change to your PR that was made changed the mixer slightly so that yaw axis moves would not cause more throttle movement unless it had to. Basically me and a few others complained that it seemed to sort of "float" during sharp turns due to yaw adding thrust. Without the yaw compensation if you just hovered and gave a little yaw you would see the drone move up due to this. Added some code to correct and compensate for that.

Later I found out that this compensation would create a yaw value to the motors that would shrink as more roll/pitch was applied to the mixer. So you would end up with less yaw than your controller was commanding during roll/pitch moves. This fixes that so that yaw control stays the same regardless of pitch/roll (unless clipping starts to be involved in which case roll/pitch/yaw are all clipped). I should probably update this code so that these code changes are only applied if you have the mixer_yaw_throttle_comp turned on.

Looking over the code again I would hope that there is a more cpu effective way to achieve this effect. Thanks for taking a look @tylercorleone and thanks for the original implementation! I've been flying this change for a while and don't notice a huge flight performance difference, but it does seem to be a little mathematically better way to mix the pidsums while the mixer_yaw_throttle_comp is enabled.

@nerdCopter
Copy link
Member

nerdCopter commented Oct 31, 2022

would constrainf help here in any way? or constrain_boundaries ?

@nerdCopter
Copy link
Member

  • @Quick-Flash , please check last comment.
  • i've been flying this exclusively on 5", 6", 7" without any errors -- 8K and 10.67 K loops.

@Quick-Flash
Copy link
Member Author

  • @Quick-Flash , please check last comment.
  • i've been flying this exclusively on 5", 6", 7" without any errors -- 8K and 10.67 K loops.

Looks good!

@nerdCopter nerdCopter self-requested a review March 4, 2023 13:40
@skylupop
Copy link

skylupop commented Mar 5, 2023

Hi @Quick-Flash, @nerdCopter, reading the descriptio:
m1 = -roll+pitch-yaw = 0.09 = -0.03roll+0.03pitch-0.3yaw
the contribute is not "distributed" in that way, on every single motor but the total motors' contribute is what makes the quadcopter roll, pith and yaw.

For example, if I'm not wrong, given:

m1 = -roll+pitch-yaw = 0.09
m2 = -roll-pitch+yaw = 0.33
m3 = +roll+pitch+yaw = 0.73
m4 = +roll-pitch-yaw = 0.49

by looking at signs I can deduce that motors 1 and 2 will contribute "negatively" to roll movements (it would be better if they stay still or reverse), so the total roll contribute will be:
m3 + m4 - m1 - m2 = 0.73 + 0.49 - 0.09 - 0.33 = 0.8
while for yaw:
m2 + m3 - m1 - m4 = 0.33 + 0.73 - 0.09 - 0.49 = 0.48

total roll contribute is higher because the "0.2" input to the controller was thrust difference and not motor output, while yaw-related input is already proportional to motors' RPM.

P.S. I'm tylercorleone using my work account, sorry :)

@Quick-Flash
Copy link
Member Author

Hi @Quick-Flash, @nerdCopter, reading the descriptio:
m1 = -roll+pitch-yaw = 0.09 = -0.03roll+0.03pitch-0.3yaw
the contribute is not "distributed" in that way, on every single motor but the total motors' contribute is what makes the quadcopter roll, pith and yaw.

For example, if I'm not wrong, given:

m1 = -roll+pitch-yaw = 0.09
m2 = -roll-pitch+yaw = 0.33
m3 = +roll+pitch+yaw = 0.73
m4 = +roll-pitch-yaw = 0.49

by looking at signs I can deduce that motors 1 and 2 will contribute "negatively" to roll movements (it would be better if they stay still or reverse), so the total roll contribute will be:
m3 + m4 - m1 - m2 = 0.73 + 0.49 - 0.09 - 0.33 = 0.8
while for yaw:
m2 + m3 - m1 - m4 = 0.33 + 0.73 - 0.09 - 0.49 = 0.48

total roll contribute is higher because the "0.2" input to the controller was thrust difference and not motor output, while yaw-related input is already proportional to motors' RPM.

P.S. I'm tylercorleone using my work account, sorry :)

I got the data without using any thrust linear, where roll/pitch/yaw should keep their ratios regardless of extra roll or pitch input. It's not to tricky to pull out the mixer code and run simulations based on the desired r/p/y and then back calculate things based on the motors to see the actual outputs it gives.

@nerdCopter
Copy link
Member

i can produce BBL files upon request. i'm unsure how to analyze them as proof or disproof however.

@nerdCopter
Copy link
Member

@skylupop
Copy link

skylupop commented Mar 7, 2023

Hi @Quick-Flash!

It's not the thrust linearization thing the main "problem" (although it should be kept in consideration it is the only reason because the 2PASS mixer exists: handling roll and pitch separately from yaw because of their different nature :) ) but the steps like this: m1 = -roll+pitch-yaw = 0.09 = -0.03roll+0.03pitch-0.3yaw
Looking at a single motor output cannot give you any hint of what is happening if you don't look at the opposite motors.
E.g. a motor could be at 100% but not producing any roll, that is m1 = 100 doesn't mean 33.3% roll, pitch and yaw!

As I wrote you in a message we could play with the very first code proposed, e.g. here https://github.com/emuflight/EmuFlight/blob/master/src/main/flight/mixer.c#L1015. We could stard from there and tweak the very basic way we mix values avoiding additional "fixes".

"When mixing an even amount of roll and yaw you would end up with the motors producing more roll than yaw" this is due to thrust normalization. Also it's difficult to compare roll and yaw :) you could compare the percentage of what the user is requesting and how many of that request is being applyed instantaneously.

@nerdCopter it would be nice to see a log describing the issue of the initial code and then we could try to "fix" it!

@nerdCopter
Copy link
Member

nerdCopter commented May 3, 2023

merging. i rather fly it than not fly it.
i do prefer proper analysis as @tylercorleone suggested, but no effort is being made.

@nerdCopter nerdCopter merged commit 1ff18fc into master May 3, 2023
@nerdCopter nerdCopter deleted the 2pass-yaw-fix branch May 3, 2023 14:02
@nerdCopter nerdCopter restored the 2pass-yaw-fix branch June 6, 2023 15:00
@nerdCopter nerdCopter changed the title Fix the correction yaw gives in 2pass Fix the correction yaw gives in 2pass motor-output-mixer Aug 21, 2023
@nerdCopter nerdCopter changed the title Fix the correction yaw gives in 2pass motor-output-mixer Fix the correction yaw gives in 2pass (Motor Output Mixer) (Thrust Linearizatio Feb 14, 2024
@nerdCopter nerdCopter changed the title Fix the correction yaw gives in 2pass (Motor Output Mixer) (Thrust Linearizatio Fix the correction yaw gives in 2pass (Motor Output Mixer) (Thrust Linearization) Feb 14, 2024
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.

None yet

4 participants