-
Notifications
You must be signed in to change notification settings - Fork 18.3k
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
Copter: Voltage compensation to throttle/pwm is used in many places in motor output function, is it used repeatedly? #23575
Comments
Sorry, this is a little tricky to follow, could you open a PR with the simplifications you suggest? We have some nice tests for motors now so we should be able to prove its the same. I think the idea is that the result would be the same? |
Also please review #23237 this might change your maths so there is an option being introduced |
Hi @luweiagi, I always like seeing your code reviews! I have to be equally carful with my replies so it will take me a little time. The motor mixer was a difficult thing to get right (or at least right enough). I had a couple confusing aspects to deal with:
I found it easier to write develop the mixing and limiting code in a strict -1 to 1 or 0 to 1 range and then scale the input and output back to the instantaneous actuator range. This is why we scale everything by a gain at the beginning and again before we convert to the pwm output. I figured when I got it right I could play with the code to improve readability, speed, or simplicity once I got the math working correctly. I say all this before reading your issue in detail, I would not be surprised if you are highlighting aspects of this. Your opening statement for example:
In (1), I am confused why you wrote this:
This is not correct and I wonder if your statements below this assume this.
Neither, rpm = kv * (v - iR) So as the load builds up the rpm drops below the perfect no-load linear voltage to rpm relationship defined by kv. So basically the more losses in the system the more non-linear the relationship is. The current is proportional to torque so the propeller drag increases the losses and rpm. We assume thrust is aproximatly proportional to rpm^2 but these losses reduce the rpm. So we have an approximation that fits this reasonably well before propeller stall. This is where the parameter thrust_curve_expo is used. We assume the thrust curve is somewhere between a linear rpm and rpm^2 relationship, where it moves towards the linear end as losses increase. This is because losses become more significant as rpm increases. This is why our maximum thrust varies with battery voltage:
Yes, I am sure this is true but it is also a useful value to keep in mind to understand what is going on. We command thrust between zero and _lift_max on each actuator, that is also where we start seeing saturation. _lift_max at full battery is what we consider 100% thrust. I have not sat down and went through a simplification process on this code yet so I am very open to the idea that it may be easier to understand without this variable. Thanks for reading through this. There is a lot of potential to clean up the Motor Mixer code. Pete has done some great work but there are a lot of places we can make it easier to understand and read. Not relevant just yet but we probably shouldn't have the air density here but instead part of lift max.
|
Thanks @lthall , Before I see the detail of your reply and think deeper, I want to make sure what the
Does ================================== another point I found, witch is also irrelevant to the question, I just mention it by the way:
namely, we must apply the thrust linearisation, so we add y=x. But I think it is not the real reason. |
is the basic motor model. So you can see that when you have zero torque (zero current) you do get a linear rpm to voltage drive relationship. The pwm command to the esc is equal to the voltage drive. The maximum voltage drive is the battery voltage. R is the internal resistance of the motor, not the battery. I think you summarised the battery resistance estimation stuff well.
Because when a power system becomes very lossy, linear becomes a better approximation, and then starts going the other way. I have actually had a DC motor copter with a negative expo! What is basically happening is the losses are building up faster than the thrust :) The other thing to keep in mind is we don't start at zero thrust. The higher we set the minimum PWM the more linear the rest of the curve is because we assume zero thrust request is really zero thrust. The one thing I can say about my work here is I can justify every single decision I made. I am happy to explain it, it helps me review those decisions and the code that was supposed to represent them :) |
Hi, @lthall The following diagram is the equivalent circuit diagram of a DC motor: I do not know if I am right, but the result of my formula is like this... |
Sorry @luweiagi, I don't understand what you are trying to tell me. |
@lthall Sorry for my unclear description. Let me explain my purpose in doing the previsous reply. I do not know if pwm=f(thrust) above (1) If it is just an empirical formula, I will no longer try to seek a theoretical explanations and just try to understand the scene. |
@luweiagi I love how much effort you got to, I really appreciate it!!
It is an empirical formula. As your equations above show, when the Cl/Cd is high the PWM to thrust curve is approximately Thrust ~ PWM ^2 and becomes more linear as the Cl/Cd drops. As you point out the expo equation is not derived from the ideal propeller/motor model however:
I chose it because the exponential curve is:
I was able to get my hands on approximately 110 thrust curves of various propellers/motor combinations, ranging from 5 inch to 30 inch. I used that data to ensure I was able to get a reasonable fit using the simple expo equation.
I think it is pretty good. I always struggle a little with the propeller equations as I have no formal aerodynamics education and from what I can see the Cl and Cd vary a lot based on inflow and rpm. I have not had the time to go back through the motors libary to see how much easier I can make it to understand and read so I suspect there is a lot we can do to improve this code! Looking at your results above I also wonder if we can get slightly better results using a curve based on your equation above as the shape at the low rpm's vary a little from what we are using now. I would like to have a chat sometime @luweiagi, ping me on discord or discuss if you comfortable with that. |
Hi, @lthall I'm sorry for not replying you in time because I have a long holiday. (1) Thank you for your patient communication and explanation. Now I think I have almost completely understand the moter output function. (2) I found two places which can be modified in the ArduPilot Motor Thrust Fit
from
to
I have momdified this file and save to new ArduPilot Motor Thrust Fit (3) I think it is interesting to optimize the motor output function with possible correct cognition: (4) If you have any poblem or want to call me, just send me a email: luweiagi@163.com and I will reply once I see it.
No problem! I will go to the discord and learn how to use it. |
Hi,
voltage compensation to throttle/pwm is used in many places in motor output function. I think it is used repeatedly, there is no need to use it so many times.
The current situation is as follows:
voltage compensation is used in three functions in output():
(1) the first function:
_lift_max = _batt_voltage_resting_estimate / _batt_voltage_max
(2) the second function:
compensation_gain = 1 / _lift_max
and
throttle_thrust = get_throttle() * compensation_gain;
(3) the third function:
use
_lift_max
andbattery_scale = 1 / batt_voltage_filt
we use simplified throttle->pwm as the key formula for convenience and simple:
In above formula, voltage compensation used in several times:
(1) thrust:
we can get
(2) _lift_max:
(3) battery_scale:
so,
So, you see, there is no need to create variable
_lift_max
and no need to compensite in output_armed_stabilizing likethrottle_thrust = get_throttle() * compensation_gain;
. Just using battery_scale is enough.I wonder to know if votage is linear to pwm/rpm? or votage is linear to force/thrust?
if votage is linear to pwm/rpm, is below situation right?
suppose votage_full = 10v, and votage_now = 8v, and we need pwm = sqrt(thrust) = 1000, but for the season of votage_now is low, so the actual pwm is 1000*(8/10)=800? so we must let pwm go to 1000/(8/10)=1250, and the actual pwm is 1250*(8/10)=1000?
If my guess is right, then I think it is right that putting voltage compensation(battery_scale) outside the sqrt(thrust), it is no problem. But _lift_max is redundant, because _lift_max * (1 / _lift_max ) = 1 inside sqrt(thrust).
by the way, I noticed that in
compensation_gain
there is air density compensation, This is ok and nessasary.So, pwm can be
To summarize, I think there is no need to reserve _lift_max.
The text was updated successfully, but these errors were encountered: