Skip to content

Transform

drone_controllers.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.

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).

rotor_vel2body_force(rotor_vel, rpm2thrust)

Convert rotor velocities to motor forces.

rotor_vel2body_torque(rotor_vel, rpm2thrust, rpm2torque, L, mixing_matrix)

Convert rotor velocities to motor torques.

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.

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]

The transform module provides utility functions for converting between different physical representations of quadrotor motor state.

Motor force / rotor velocity

motor_force2rotor_vel

Invert the quadratic thrust curve \(f = a + b\,\omega + c\,\omega^2\) to recover rotor speed from motor force:

import numpy as np
from drone_controllers.core import load_params
from drone_controllers.mellinger import force_torque2rotor_vel
from drone_controllers.transform import motor_force2rotor_vel

params = load_params(force_torque2rotor_vel, "cf2x_L250")
rpm2thrust = params["rpm2thrust"]

forces = np.array([0.05, 0.08, 0.10, 0.05])  # N per motor
rpms = motor_force2rotor_vel(forces, rpm2thrust)
rpms.shape  # (4,)

rotor_vel2body_force

Sum rotor forces into a body-frame force vector. Only the z-component is nonzero for an X-frame quad:

import numpy as np
from drone_controllers.core import load_params
from drone_controllers.mellinger import force_torque2rotor_vel
from drone_controllers.transform import rotor_vel2body_force

params = load_params(force_torque2rotor_vel, "cf2x_L250")
rpm2thrust = params["rpm2thrust"]

rotor_speeds = np.full(4, 12_000.)  # RPM
body_force = rotor_vel2body_force(rotor_speeds, rpm2thrust)
body_force.shape  # (3,) -- x, y are zero; z is total thrust

rotor_vel2body_torque

Compute body-frame torques from individual rotor speeds using the mixing matrix.

PWM conversions

force2pwm / pwm2force

Linear conversion between thrust in Newtons and the PWM signal sent to the motors:

import numpy as np
from drone_controllers import mellinger
from drone_controllers.core import load_core_params
from drone_controllers.transform import force2pwm, pwm2force

core = load_core_params(mellinger, "cf2x_L250")
thrust_max = float(core["thrust_max"])
pwm_max    = float(core["pwm_max"])

thrust = np.array([0.05, 0.10])
pwms   = force2pwm(thrust, thrust_max, pwm_max)
thrust_recovered = pwm2force(pwms, thrust_max, pwm_max)
np.allclose(thrust, thrust_recovered)  # True