PX4 / PX4-SITL_gazebo-classic

Set of plugins, models and worlds to use with OSRF Gazebo Simulator in SITL and HITL.
http://dev.px4.io/simulation-gazebo.html
367 stars 787 forks source link

Documentation: What is the math behind the Motor Model? #110

Closed TSC21 closed 4 years ago

TSC21 commented 7 years ago

Hi guys,

So here's the thing: I'm building a VTOL model similar to the standard VTOL which has some specifications in terms of motor setup: for example, the front motors have less torque than the back motors, which are more powerful in order to keep the vehicle balanced. The pusher motor is also different from those.

Having some time already working with Gazebo SITL, I found out that most of the vehicle models have the same motor models, pretty similar configurations and even weights. The thing is, if one wants to create his own vehicle model, with proper inertia matrix and weight, it also needs to have the motors model with the correct setup.

So after some research, and trying to figure out how to compute the different parameters that compose the motor model in the SDF config, I came up with the following math for those:

Ω or Max Rotational Velocity = Kv * Max Applied Voltage * Max Motor Efficiency * 2π / 60 Motor Constant = Thrust / (Ω) ² Moment Constant = 60 / (2π * Kv) Rotor Drag Coefficient = Thrust / (ρ * (Kv * Max Applied Voltage * Max Motor Efficiency / 60) ² * Propeller diameter ⁴) Rolling Moment Coefficient = Using SST turbulence model from reference, and bent/round wings/propellers: ~0.0220 for angle of attack smaller than 16 degrees - I'm keeping this defaulted to 1E-06 for now.

where, Kv [RPM/V] Max Thrust [N] Max Applied Voltage [V] Ω Rotor angular velocity [rad/s] ρ Air density at 20ºC: 1.2041 [kg/m³]

The Motor Time Constant is still something I don't know how to get it.

So what I ask is for help from someone that dedicated time writing the motor model plugin and that knows how's the math structured so to confirm or correct the math above. This will be helpful to everyone facing the same trouble when wanting to properly simulate their vehicle models, and not just copy paste from the existing models.

TSC21 commented 7 years ago

Just to let you know - using the math above I was able to get a 20kg VTOL model to fly, but I'm getting a strange behavior where the vehicle, so to move into a certain setpoint, back drifts and rotates 180 degrees in yaw, and just then it starts moving into the commanded position (so basically moving on its back into the commanded position). I can confirm that this behavior is due to some weird value I'm probably inserting on the motors model parameters (computed from the math above) which makes the vehicle drift on the back motors before then moving to the commanded position, which is something weird to watch. The RPM, Thrust and Voltage are given by a table available on the motors vendor website.

TSC21 commented 7 years ago

I believe this will also help solving #78.

TSC21 commented 7 years ago

@LorenzMeier, @tumbili, @ChristophTobler, @devbharat are you able to give some insights here? The purpose for this is that anyone that wants to build is own vehicle model is able to properly do it. Thanks in advance!

LorenzMeier commented 7 years ago

Looking into this.

TSC21 commented 7 years ago

Looking into this.

Awesome! Thank you!

TSC21 commented 7 years ago

@LorenzMeier were you able to make any progress in this?

AlexandreBorowczyk commented 7 years ago

Hi, I'm also looking into the motor model. @TSC21 I'm curious here you found the equation for the Rotor Drag Coefficient? I've used the data for a small 7 inch, 800g thrust, 1450 kv propeller-motor and the rotor drag is very high.

TSC21 commented 7 years ago

@TSC21 I'm curious here you found the equation for the Rotor Drag Coefficient?

I'm still waiting that someone clarifies and confirms this in a clear way.

AlexandreBorowczyk commented 7 years ago

@TSC21 I understand, I'm just curious about where the equation come from. If you don't mind sharing, I would like to look into it.

TSC21 commented 7 years ago

@AlexandreBorowczyk - http://m-selig.ae.illinois.edu/props/propDB.html (CT equation). Maybe I'm mixing the thrust coefficient with the rotor drag?

TSC21 commented 7 years ago

Yeah I was doing something wrong here. I'm applying the corrections now (though is kinda hard to guess what units are being used on Gazebo side).

TSC21 commented 7 years ago

Ok for the rotor drag, I could compute it with this reference plus the above reference: Drag Coefficient (CD) = (CT)^1.5 / (CP * 0.707) // For static conditions, figure-of-merit is calculated where, CP = Power_In / (ρ * (Kv * Max_Volt * Max_Eff / 60) ³ * Propeller_diam ⁵) CT = Thrust / (ρ * (Kv * Max_Volt * Max_Eff / 60) ² * Propeller_diam ⁴) ρ = Air density at 20ºC: 1.2041 [kg/m³]

TSC21 commented 7 years ago

@AlexandreBorowczyk can you test the formulas above and check if it makes sense now?

TSC21 commented 7 years ago

The vehicle is pretty stable right now but I'm still getting the stupid behavior of rotating 180 degrees on yaw. @LorenzMeier any points/tips on what can be happening? May the inertial matrix of the vehicle interfere with that?

AlexandreBorowczyk commented 7 years ago

@TSC21 I've looked at the reference you pointed to as well as into the code. I suspect the equation for the Moment Constant and Rotor Drag Coefficient to be incorrect.

The moment constant is used as such in the code -turning_direction_ * force * moment_constant_ which mean that to determine this value you either need to have torque data or their is a rule on thumb for the ratio of force to torque for common propellers. As for Rotor Drag Coefficient, I believe it's the resistance to linear motion of the rotor disk and not the conventional airfoil drag coefficient. I'm trying to dig deeper in the document referenced in the code "The True Role of Accelerometer Feedback in Quadrotor Control" to see how it can be evaluated.

As for the 180 degrees yaw problem, check the orientation of your IMU link in our model make sure it is correctly oriented.

TSC21 commented 7 years ago

The moment constant is used as such in the code -turning_direction_ * force * moment_constant_ which mean that to determine this value you either need to have torque data or their is a rule on thumb for the ratio of force to torque for common propellers.

I got the above from https://en.wikipedia.org/wiki/Motor_constants - Motor Torque Constant.

As for Rotor Drag Coefficient, I believe it's the resistance to linear motion of the rotor disk and not the conventional airfoil drag coefficient. I'm trying to dig deeper in the document referenced in the code "The True Role of Accelerometer Feedback in Quadrotor Control" to see how it can be evaluated.

I already looked at that reference without luck. Also, I believe that this drag is the combination of the actuation of the motor and the propeller, and that's why it is included both thrust constant and power in constants. That's also math I found available in the proppeler database. But I can be wrong of course. What I don't think it make sense is that we have to be looking for this math models when this could be properly documented already by who created the plugins (open-source contributions usually indicate how can people use and modify the code).

As for the 180 degrees yaw problem, check the orientation of your IMU link in our model make sure it is correctly oriented.

Already checked that many times and with different orientations with no luck. Though I can confirm that if I send a setpoint of 180 degrees on yaw, it goes forward as expected.

TSC21 commented 7 years ago

@AlexandreBorowczyk do you have news on this?

AlexandreBorowczyk commented 7 years ago

@TSC21

I got the above from https://en.wikipedia.org/wiki/Motor_constants - Motor Torque Constant.

I see however this is not the coefficient we are looking for. I believe the best way to obtain this coefficient would be from experimental data. However, I also think that is you use a similar type propeller (airfoil shape and number of blades) the force to moment ratio should not be very different and you can use the default.

As for the Rotor Drag Coefficient, I see the "The True Role of Accelerometer Feedback in Quadrotor Control" paper point to a book "Helicopter Theory" by W. Johnson which I have so I will look into it and see what I can find.

However, I don't believe a motor modelisation error is the source of your issue.

TSC21 commented 7 years ago

I see however this is not the coefficient we are looking for. I believe the best way to obtain this coefficient would be from experimental data. However, I also think that is you use a similar type propeller (airfoil shape and number of blades) the force to moment ratio should not be very different and you can use the default.

What leads to think it is not? From the calculations I do, it leads me to very similar values to the default ones.

As for the Rotor Drag Coefficient, I see the "The True Role of Accelerometer Feedback in Quadrotor Control" paper point to a book "Helicopter Theory" by W. Johnson which I have so I will look into it and see what I can find.

Great. This is the value that does not show consistency with the default ones on the simulation (gives a two degrees higher value, though it seems to work, besides the yaw issue).

However, I don't believe a motor modelisation error is the source of your issue.

Probably not but right now I cannot tell what is the problem right now.

TSC21 commented 7 years ago

@AlexandreBorowczyk here you can find that the rotor drag coefficient is: = D / (ρ * π * R² * (Ω * R)²), where D is the rotor drag force, R is the rotor radius and Ω is the angular velocity in rad/s, which basically becomes Rotor drag coefficient = Drag Force / (ρ * (Kv * Max Applied Voltage * Max Motor Efficiency / 60) ² * Propeller diameter ⁴). Now, when the aircraft flies level at constant velocity, all opposite forces of flight are equal. In that case the aircraft is in cruise conditions. So in that case, drag = thrust and weight = lift (https://www.grc.nasa.gov/www/K-12/airplane/ldrat.html). So we can extrapolate that Rotor drag coefficient = Thrust / (ρ * (Kv * Max Applied Voltage * Max Motor Efficiency / 60) ² * Propeller diameter ⁴) as I described on the issue description. Is this a wrong consideration on your opinion?

AlexandreBorowczyk commented 7 years ago

@TSC21, Can you repost the first link it seems not to work. Nevertheless, I believe I understand your reasoning and I see possible issue. First, it is important to differentiate between static thrust and dynamic thrust, most often for a motor-propeller combo thrust spec is the static thrust. A propeller thrust is highly dependent of the air inflow velocity so it's maximum dynamic thrust (if motion parallel to rotation axis) is must smaller than it's static thrust. In addition, the rotor drag is calculated with respect to the rotor disc motion (if you does account for wind) but the the propeller thrust is only along the rotation axis (for this simplified model). Hence, the drag=thrust cannot be used in this setting. So the equation could be correct but you would need to know the drag force to get the coefficient.

TSC21 commented 7 years ago

@TSC21, Can you repost the first link it seems not to work.

It's a file it should automatically download - www.dtic.mil/cgi-bin/GetTRDoc?AD=ADA224493.

Hence, the drag=thrust cannot be used in this setting. So the equation could be correct but you would need to know the drag force to get the coefficient.

And how do you expect to find the drag force without simplifying the model for static thrust?

TSC21 commented 7 years ago

@AlexandreBorowczyk any news?

AlexandreBorowczyk commented 7 years ago

@TSC21 I finally got the time to do a little bit of algebra and look at the simplifying the H-Force equation. I've set to zero the terms for vertical and rotation motion and ignored the blade flapping and obtain a expression that's matches the form H-Force = - coefficient * motor_vel * body_perp_vel. Without any guarantee on the accuracy of the result: H-force = - 0.25 * (0.5 * λ * θt * a - Cd) * Bt² * σ * ρ * A * Ω * body_perp_vel. with

σ = b*c*R / A (rotor solidity, ratio of blade to rotor area)

where

Vt= Ω * R (tip speed)

A= π * R^2 (rotor area)

λ ≈ √(Ct/2) @ hover (inflow velocity ratio)

θt: propeller twist [deg]

a: lift curve slop (of the airfoil) [cl/deg]

Bt: tip loss factor (~ 0.97)

b: number of blades

c: thrust-weighted chord [m]

ρ: air density [kg/m³]

R: blade length or rotor radius [m]

Ω: rotor rotational speed (rad/s)

To implement this you need first to evaluate your lift and drag coefficient in a static setup. I would try to take a few points of data and average out the Ct and Cd obtain.

Ct = T / (ρ * π  * R² * Vt²)

Cd = 8 * Pprof / (σ * ρ * π  * R² * Vt³)

Pprof= Torque (N.m) x Ω

Consequently you need to have a rought idea of the propeller twist and airfoil shape and be able to measure the Thrust, torque and RMP in a static setup.

I could do a bit more math to include the effect of coning at hover but you would need to know the rotor blade inertia. Also due to the approximation and simplification this equation is more accurate at level flight and low advancement speed.

However, I would recommend to use SITL to evaluate "Top Level functionality" rather then physical configuration functionality as the motor_model and liftdrag (I believe you are working on a VTOL) plugin implementations are of limited accuracy.

TSC21 commented 7 years ago

Thanks for the effort @AlexandreBorowczyk. But in a general perspective, I think the equation you came up with come to be more complicated than expected. Are we to suppose that the person who wrote the plugin use this type of math to get the values, or would be something more standard that could be find on a table (like http://m-selig.ae.illinois.edu/props/propDB.html)?

TSC21 commented 7 years ago

Now I'm confuse: what does the H-Force represent here? Aren't we trying to get the rotor drag coefficient?

AlexandreBorowczyk commented 7 years ago

@TSC21

I think the equation you came up with come to be more complicated than expected

rotors are inherently very complex. I am concerned the equation to be over simplified to get accurate result from propeller geometry.

Are we to suppose that the person who wrote the plugin use this type of math to get the values

From the code on rotors_simulator, I think they are still working on it:

lambda1_ = 0.0001; //TODO(ff): find a more accurate parameter value

would be something more standard that could be find on a table (like http://m-selig.ae.illinois.edu/props/propDB.html)

Some of these equations are used in the H-force equation. However, you need to be careful, this website deals with propellers not rotor. For example, on the UIUC site, I believe the advancement ratio to be defined as along the axis of rotation.

what does the H-Force represent here? Aren't we trying to get the rotor drag coefficient?

From "The True Role of Accelerometer Feedback in Quadrotor Control" cited in the code. image with https://github.com/ethz-asl/rotors_simulator/commit/2c58d8f4d06c6837dae1ee6b5b539ddfa83a7cc9

From my perspective, H-Force = - coefficient * motor_vel * body_perp_vel is most likely already a oversimplification which prevents the "rotor drag coefficient" to be determined parametrically. I assume the value maybe chosen as a good fit or determined by model matching from experimental data.

EliaTarasov commented 6 years ago

@TSC21 Just a guess: maybe it's better to replace existing motor model with more broadly used approach? Previously i used JSBSim propeller model. The math is relatively complex, but not too much. Basically the idea is that if you have Power and Thrust coefficients either from windtunnel data or external computer utility then forces and moments are correctly calculated. The advantage of this approach is that such propeller's model and the way of calculation is more broadly used and confirmed by practice.

Of course, this would require more efforts and should be discussed.

TSC21 commented 6 years ago

@EliaTarasov yes that is a possibility to consider, but in a first stage I think it would be goood to actually understand what math are we working with here.

EliaTarasov commented 6 years ago

@TSC21 I followed equations you mentioned in the first post and failed to achieve stable results. The motor's thrust force is almost fine at 50% takeoff throttle, but copter fly skyhigh at first seconds. I'm pretty sure masses and MoI for the copter's body and props are correct. Have you noticed such an issue before?

TSC21 commented 6 years ago

@EliaTarasov these equations are still to confirm.

EliaTarasov commented 6 years ago

Using information from the vendor website and the expressions for Rotor Drag Coefficient and Rolling Moment Coefficient i was able to fly my model in a way that might be called as "stable" flight. There is the problem with thrust - it somehow "jumps" and increases very fast. However this might be due to thrust-to-weight ratio equals almost 3. Seems like air drag is simulated only for rotors, so full throttle may give 2g acceleration to the body.

TSC21 commented 6 years ago

Using information from the vendor website and the expressions for Rotor Drag Coefficient and Rolling Moment Coefficient i was able to fly my model in a way that might be called as "stable" flight. There is the problem with thrust - it somehow "jumps" and increases very fast. However this might be due to thrust-to-weight ratio equals almost 3. Seems like air drag is simulated only for rotors, so full throttle may give 2g acceleration to the body.

@EliaTarasov so does your experiments confirm the above equations? Is there any detail to add? Would be good to have all this confirmed so this can be documented.

EliaTarasov commented 6 years ago

@TSC21 I still have some troubles with thrust. When i solve it i provide additional feedback. Thanks for the help!

EliaTarasov commented 6 years ago

@TSC21 Did you tune any pid gain for your custom model? My thrust problem still holds. I just thought it could be control problem.

EliaTarasov commented 6 years ago

@TSC21 I was able to finish my model and can confirm the following equations: Ω or Max Rotational Velocity = Kv * Max Applied Voltage * Max Motor Efficiency * 2π / 60 Motor Constant = Thrust / (Ω) ² Rotor Drag Coefficient = Thrust / (ρ * (Kv * Max Applied Voltage * Max Motor Efficiency / 60) ² * Propeller diameter ⁴) Rolling Moment Coefficient

But somehow Moment Constant = 60 / (2π * Kv) does not fit. It's around 100 times lower than what can be derived from motor spec. I use torque data from the motor specs for now.

EliaTarasov commented 6 years ago

Update: equation for Moment Constant = 60 / (2π * Kv) gives coefficient that is about 2 times higher than what can be derived from the motor spec.

EliaTarasov commented 6 years ago

Playing with timeConstantUp and timeConstantDown can also be useful especially for big motors with long propellers. All in all my experience tells that these equations might be good enough for approximation.

TSC21 commented 5 years ago

@EliaTarasov something from your findings can actually be brought into the documentation in order to complement the content of this issue?

All in all my experience tells that these equations might be good enough for approximation.

So do you confirm all the equations stated here except the moment constant?

EliaTarasov commented 5 years ago

Moment Constant = 60 / (2π * Kv) gives 41% overshoot compared to motor spec, and Max Rotational Velocity = Kv * Max Applied Voltage * Max Motor Efficiency * 2π / 60 gives 16% overshoot. These values are calculated on 75% thrust. 50% thrust gives slightly better result but not much. So if someone doesn't have motor specs then modelled vehicle has substantually better performance then the real one. However this might be negligible depending on what task is needed for particular model.

So do you confirm all the equations stated here except the moment constant?

I think these equations can be confirmed as a first step to quickly get flyable model. If this is not enough then more additional data is needed (motor specs, etc).

bozkurthan commented 5 years ago

Hello @TSC21 @EliaTarasov,

I would to ask question about values of Iris and values of Typhoon_H480.

We have the same values except maxRotVelocity for Iris and Typhoon_H480.

      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1500</maxRotVelocity>  <!--Iris =1100-->
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>3</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>

Is it normal for iris and Typhoon to have the same motor capacity?

And as far as I know rotorVelocitySlowdownSim has important role for simulation. However, when I investigated gazebo_motor_model.cpp plugin source, I found that we are forcing motor models' simulation time to 10.

https://github.com/PX4/sitl_gazebo/blob/2adc86b5bf84543091470966caf33c3b4f3ee666/src/gazebo_motor_model.cpp#L132

TSC21 commented 5 years ago

If you check all the SDF models you will understand they all use the same motor model, just for the sake of simplifying the sim parameters. And it's not forcing to 10. Check the messafe definition and you will see that's the default value in the case that thr SDF parameter does not exist.

EliaTarasov commented 5 years ago

In addition: to find out the exact values for timeConstantUp and timeConstantDown you may want to do the motor speed test. Others characteristics may have been calculated as shown above.

TSC21 commented 5 years ago

@hamishwillee I think we reached a state where we can actually come up with something useful on the docs, where we guide people on how they can add their own model for their motors. This would be a subset of a bigger topics, which would be: how can people model their own aircraft as an usable SDF for sitl_gazebo.

hamishwillee commented 5 years ago

@TSC21 Sounds great. I am way behind the curve for this, and not very familiar with ROS. Is this an extension of the discussion in https://github.com/PX4/Devguide/issues/398

I guess I'm saying - how do you want to approach this?

TSC21 commented 5 years ago

@TSC21 Sounds great. I am way behind the curve for this, and not very familiar with ROS. Is this an extension of the discussion in PX4/Devguide#398

This is not related to ROS, as Gazebo is a simulator that can run without ROS. Yes it's basically the extension of that discussion, even though I think the discussion on that issue moved to the PX4 side of things. The idea is to firts understand how can you model things on Gazebo, and then how you can add the model in the PX4 side.

I guess I'm saying - how do you want to approach this?

We should probably define first the structure of the documentation for this same purpose, where you would include topics has importing an URDF from SolidWorks and convert it to an SDF, what plugins to include in the model, modelling the motors, modelling the control surfaces, etc. It's probably something to create on a document or even in an issue on the devguide, so others can also add their input. Then we could start tackling each of these topics at a time.

jannsta1 commented 5 years ago

I tried making my own model a while ago using mainly experimental data - e.g. using bifilar pendulum to measure inertia and a home made thrust rig to measure motor thrust and torque. I'm not really sure how this kind of approach compares to purely theoretical approaches (I didn't really finish/evaluate my model) but I guess in some circumstances it should be more convenient to go down this route - e.g. calculating inertia tensor for an off-the shelf airframe build. Would it be possible / make sense to include some information about such experimental procedures here too? I guess a method for model evaluation would be another nice to have.

TSC21 commented 5 years ago

@jannsta1 sure. Anything you can suggest and contribute with is welcomed!

jannsta1 commented 5 years ago

OK @TSC21, will aim to at least write up what I did as a starting point and report back on here. Hopefully people with more knowledge in this area can expand on it in future.

TSC21 commented 5 years ago

@jannsta1 probably the best place to do it would be in PX4/Devguide#398. From there we can expand into a PR where we address all the required topics for creating a new model for PX4 sitl_gazebo.