rotors_simulator
rotors_simulator copied to clipboard
Documentation: What is the math behind the Motor Model Plugin?
Hi guys,
I'm duplicating https://github.com/PX4/sitl_gazebo/issues/110 since you are using the same plugin and since, after this is answered, it would be useful for both parts.
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 is 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:
Max Rotational Velocity = Kv * Max Applied Voltage * Max Motor Efficiency * 2π / 60
Motor Constant = Thrust / Max Rotational Velocity ²
Moment Constant = 60 / (2π * Kv)
Rotor Drag Coefficient = Thrust / (Air density * (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]
Max Rotational Velocity [rad/s]
Air density at 20ºC: 1.2041 [kg/m³]
The Motor Time Constant is still something I'm 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.
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.
Can someone give a hand here please? Thank you!
Usually the motor dynamic behavior is simplified as a first order system, with respect to the rotor velocity. Time constant correspond to the time in second needed for the rotor to reach 63.2% of commanded rotational speed. It is a rough estimate, but holds true if the step sizes stays similar, which is the case for quadcopters.
Your math about the coefficient seems correct to me, although I usually get those values from experiment setups, by measuring the thrust and drag torque in different rotational speed.
I am not part of the dev team so just personally experience throwing in here :)
@ffurrer As you first introduce the Rotor Drag Coefficient parameter, do you have insight on how to obtain a numerical value for it?
I am experimenting similar problems trying to edit the iris to become a 20 kg quadcopter for which I have all the parameters from the vendor website (both uav and rotors). Is there any documentation out there? The only thing I have found are @TSC21 formulas.
I am also curious about what the rolling moment is? What force generates this moment? According to this paper: http://www.i3s.unice.fr/~allibert/Publis/IFACWC17.pdf, the rolling moment should be dependent of the turning direction of the propellers (see equation 10).
Hi, So can someone tell me what these values are
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1500</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
And how do I calculate hovering thrust/throttle position from these? Thanks
what is the unit of max motor efficiency used here? and how it has been derived ?