Skip to content

Commit 10785ef

Browse files
committed
Updated brushless params based on new data.
1 parent ed91ca4 commit 10785ef

File tree

1 file changed

+15
-14
lines changed

1 file changed

+15
-14
lines changed

rotorpy/vehicles/crazyfliebrushless_params.py

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,13 @@
22
Physical parameters for a quadrotor. Values parameterize the inertia, motor dynamics,
33
rotor aerodynamics, parasitic drag, and rotor placement.
44
Additional sources:
5-
https://bitcraze.io/2015/02/measuring-propeller-rpm-part-3
6-
https://wiki.bitcraze.io/misc:investigations:thrust
7-
https://commons.erau.edu/cgi/viewcontent.cgi?article=2057&context=publication
5+
"How to Model Your Crazyflie Brushless", Grafe et al. 2026. https://arxiv.org/pdf/2603.05944
6+
Chapter 6 in "Real Time Local Wind Inference for Robust Autonomous Navigation", PhD Thesis, Folk 2026.
87
Notes:
9-
k_thrust is inferred from 14.5 g thrust at 2500 rad/s
10-
k_drag is mostly made up
8+
Values are for the Crazyflie Brushless with propeller guards.
9+
Lower level gains were hand picked and not necessarily matched to the real system.
10+
Drag values obtained from "Real Time Local Wind Inference for Robust Autonomous Navigation", slightly elevated due to additional payloads.
11+
Off-diagonal terms in the inertia should be identified in the future, but set to 0 for now.
1112
"""
1213
import numpy as np
1314

@@ -16,10 +17,10 @@
1617
quad_params = {
1718

1819
# Inertial properties
19-
'mass': 0.04, # kg
20-
'Ixx': 1.43e-5, # kg*m^2
21-
'Iyy': 1.43e-5, # kg*m^2
22-
'Izz': 2.89e-5, # kg*m^2
20+
'mass': 0.044, # kg
21+
'Ixx': 3.3e-5, # kg*m^2
22+
'Iyy': 3.6e-5, # kg*m^2
23+
'Izz': 5.9e-5, # kg*m^2
2324
'Ixy': 0.0, # kg*m^2
2425
'Iyz': 0.0, # kg*m^2
2526
'Ixz': 0.0, # kg*m^2
@@ -44,15 +45,15 @@
4445

4546
# Rotor properties
4647
# See "System Identification of the Crazyflie 2.0 Nano Quadrocopter", Forster 2015.
47-
'k_eta': 3.49e-08, # thrust coefficient N/(rad/s)**2
48+
'k_eta': 4.052e-08, # thrust coefficient N/(rad/s)**2
4849
'k_m': 7.8e-10, # yaw moment coefficient Nm/(rad/s)**2
49-
'k_d': 20.9700e-07, # rotor drag coefficient N/(rad*m/s**2) = kg/rad
50-
'k_z': 1.339e-05, # induced inflow coefficient N/(rad*m/s**2) = kg/rad
51-
'k_h': 5.74e-4, # translational lift coefficient (N/(m/s)**2) = kg/m
50+
'k_d': 5.09e-06, # rotor drag coefficient N/(rad*m/s**2) = kg/rad
51+
'k_z': 1.19e-05, # induced inflow coefficient N/(rad*m/s**2) = kg/rad
52+
'k_h': 1.11e-3, # translational lift coefficient (N/(m/s)**2) = kg/m
5253
'k_flap': 0.0, # Flapping moment coefficient Nm/(rad*m/s**2) = kg*m/rad
5354

5455
# Motor properties
55-
'tau_m': 0.005, # motor response time, seconds
56+
'tau_m': 0.050, # motor response time, seconds
5657
'rotor_speed_min': 0, # rad/s
5758
'rotor_speed_max': 3100, # rad/s
5859
'motor_noise_std': 0.0, # rad/s

0 commit comments

Comments
 (0)