transform
Transformations between physical parameters of the quadrotors.
Conversions such as from motor forces to rotor speeds, or from thrust to PWM, are bundled in this module.
force2pwm(thrust, thrust_max, pwm_max)
¶
Convert thrust in N to thrust in PWM.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
thrust
|
Array | float
|
Array or float of the thrust in [N] |
required |
thrust_max
|
Array | float
|
Maximum thrust in [N] |
required |
pwm_max
|
Array | float
|
Maximum PWM value |
required |
Returns:
| Type | Description |
|---|---|
Array
|
Thrust converted in PWM. |
Source code in drone_models/transform.py
motor_force2rotor_vel(motor_forces, rpm2thrust)
¶
Convert motor forces to rotor velocities, where f=arpm^2+brpm+c.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
motor_forces
|
Array
|
Motor forces in SI units with shape (..., N). |
required |
rpm2thrust
|
Array
|
RPM to thrust conversion factors. |
required |
Returns:
| Type | Description |
|---|---|
Array
|
Array of rotor velocities in rad/s with shape (..., N). |
Source code in drone_models/transform.py
pwm2force(pwm, thrust_max, pwm_max)
¶
Convert pwm thrust command to actual thrust.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
pwm
|
Array | float
|
Array or float of the pwm value |
required |
thrust_max
|
Array | float
|
Maximum thrust in [N] |
required |
pwm_max
|
Array | float
|
Maximum PWM value |
required |
Returns:
| Name | Type | Description |
|---|---|---|
thrust |
Array | float
|
Array or float thrust in [N] |
Source code in drone_models/transform.py
rotor_vel2body_force(rotor_vel, rpm2thrust)
¶
Compute the total thrust force vector in the body frame from motor RPMs.
The thrust from each motor is computed with the quadratic polynomial
f = a + b * rpm + c * rpm² defined by rpm2thrust, then summed and
placed in the z-component of a 3-D body-frame force vector. For a level
drone all thrust acts along the body z-axis.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
rotor_vel
|
Array
|
Motor angular velocities in RPM with shape |
required |
rpm2thrust
|
Array
|
Polynomial coefficients |
required |
Returns:
| Type | Description |
|---|---|
Array
|
Body-frame force vector with shape |
Array
|
is non-zero. |
Source code in drone_models/transform.py
rotor_vel2body_torque(rotor_vel, rpm2thrust, rpm2torque, L, mixing_matrix)
¶
Compute the total body torque from motor RPMs.
Combines two torque contributions:
- Thrust torques (roll and pitch): differential thrust across motors,
scaled by the arm length
Land themixing_matrix. - Reaction torques (yaw): aerodynamic drag torque from each propeller,
computed with the polynomial
τ = a + b * rpm + c * rpm²defined byrpm2torque, then combined via themixing_matrix.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
rotor_vel
|
Array
|
Motor angular velocities in RPM with shape |
required |
rpm2thrust
|
Array
|
Polynomial coefficients |
required |
rpm2torque
|
Array
|
Polynomial coefficients |
required |
L
|
float | Array
|
Distance from the centre of mass to each motor in metres. |
required |
mixing_matrix
|
Array
|
Matrix of shape |
required |
Returns:
| Type | Description |
|---|---|
Array
|
Body-frame torque vector with shape |