Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Unify system ID parameters #60

Open
knmcguire opened this issue Apr 27, 2024 · 1 comment
Open

Unify system ID parameters #60

knmcguire opened this issue Apr 27, 2024 · 1 comment
Labels
bug Something isn't working enhancement New feature or request

Comments

@knmcguire
Copy link
Member

We have a Webots model (proto) and a Gazebo model (SDF) of the Crazyflie. These both have different variables indicating the thrust/motor constant, part in due of different system ID models being used in both simulators.

Current situation

Webots

Webots uses the propeller model given in their documentation: https://cyberbotics.com/doc/reference/propeller
Namely

T = t1 * |omega| * omega - t2 * |omega| * V
Q = q1 * |omega| * omega - q2 * |omega| * V

Pretty sure that t2 and q2 is difficult to determine for quadcoters, So practically q1 = t1 * the arm to generate Nm?

where t1, t2 are the thrust constants and q1 and q2 are the torque constants. and omega is the motor angular velocity (unit not given but we assumed rad/s since that is the unit they use in documentation)

These are the values currently in the proto, however, I don't think that these are correct and (tbh) I don't know where they came from and not knowing which unit it is in makes it a bit difficult...

thrustConstants -4e-05 0
torqueConstants 2.4e-06 0

Gazebo

Gazebo uses a rotor model given in their documentation: https://gazebosim.org/api/gazebo/6.7/structignition_1_1gazebo_1_1systems_1_1multicopter__control_1_1Rotor.html#details

Which says:

forceConstant: A constant that multiplies with the square of the rotor's velocity to compute its thrust.
momentConstant: A constant the multiplies with the rotor's thrust to compute its moment.

It sounds to me that the motor constant should be the arm length...

In the gz.msg.actuators I'm sure that they use rad/s: https://github.com/gazebosim/gz-msgs/blob/gz-msgs10/proto/gz/msgs/actuators.proto

In the sdf we now have the following parameters:

<motorConstant>1.28192e-08</motorConstant>
<momentConstant>0.005964552</momentConstant>

These have been based on two sources:

Problem

These values seems to be way off for both webots and gazebo, but which one is accurate?

Current system ID

There has been a master thesis out that has system id' the crazyflie 2.0, which holds a lot for the 2.1.

System Identification of the Crazyflie 2.0 Nano Quadrocopter by Förster (2015). These are the values of the result:

cmd → Thrust: Thrust = 2.130295 · 10−11 * cmd^2 + 1.032633 · 10−6 · cmd + 5.484560 · 10−4
cmd → RAV:  RAV = 0.04076521 · cmd + 380.8359
Thrust → Torque: Torque  = 0.005964552 · thrust + 1.563383 · 10−5

cmd is input command and RAV is rotor angular velocity in rad/s. The latter seems to be the values that was used in CrazyS and sim_cf

Also there has been some systsem ID done by Bitcraze itself, of which the date can be found in this repo by the IMRClab. An RPM to thrust fit came to these variables:

Which is

t= [ 2.49908910e-08 -2.97972736e-05 -2.83393837e-01]
Thrust = t1 * RPM^2 + t2 * RPM + t3

The last two factors don't influence the fit much so simplified it is (with rpm to rad/s). Also, the thrust is in grams and not Newton

thrust_g = 2.5e-8 * RPM =2.5e-8 * 60 * 2π RAS= 9.42e-6 * RAS 
thrust (newton) = 9.24e6*9.81/1000 = 9.6e-8

There seems to be a difference between 9.6e-8 (latest) and 1.28e-08 (old) thrust constants.

Solutions?

Webots variables seem to be way off.. it does fly but it isn't accurate, however, the gazebo model doesn't seem to fit either. So both need to be updated and the controllers need to be tuned but that will take time.

At least this issue has the problems nicely in a referenced order since I had to always find the refencerences again every time I look into this again (and drop it because it's all over the place).

@knmcguire
Copy link
Member Author

Just to add to the webots prop model, t2 is probably the 'rotor drag coefficient' equivalent of gazebo

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working enhancement New feature or request
Projects
None yet
Development

No branches or pull requests

1 participant