You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
If we do a quick unit conversion just on the first term in la = qbar*b*(c_l_0 assuming c_l_0 is unit less means (qbar = 1.0/2.0*rho*pow(effective_airspeed,2)*s which would be [kg/m^3*m^2/s^2*m^2] ==> [kg*m/s^2]b = [m]==> kg*m^2/s^2 which is correct for torque torque = FxdN*m ==> kg*m/s^2*m ==> kg*m^2/s^2.
This has been corrected there where the variable reflects that it is a torque. #20529
Note
Unfortunately, dividing the plane rotational acceleration by the copter moments of inertia makes the quadplane sim unflyable.
Version
Went through the code on master and it looks like there are no plane moment of inertias. It's possible I'm missing it. It looks like the other sims do this.
Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ x ] Plane
[ ] Rover
[ ] Submarine
Airframe type
QuadPlane
Hardware type
SITL
Logs
Not applicable.
The text was updated successfully, but these errors were encountered:
Bug report
Issue details
I'm pretty sure there is a bug in the simulation in
SIM_Plane.cpp
,rot_accel = getTorque(aileron, rudder, thrust, force);
returns a torque not an angular acceleration. https://github.com/ArduPilot/ardupilot/blob/e2767f899ffae99b5778745bac5c9cfbbbcdfc88/libraries/SITL/SIM_Plane.cpp#L343C5-L343C15If we do a quick unit conversion just on the first term in
la = qbar*b*(c_l_0
assumingc_l_0
is unit less means (qbar = 1.0/2.0*rho*pow(effective_airspeed,2)*s
which would be[kg/m^3*m^2/s^2*m^2] ==> [kg*m/s^2]
b = [m]
==> kg*m^2/s^2
which is correct for torquetorque = Fxd
N*m ==> kg*m/s^2*m ==> kg*m^2/s^2
.ardupilot/libraries/SITL/SIM_Plane.cpp
Line 202 in e2767f8
This is a long way to say that
getTorque
is returning atorque
. This is also clear form adding the alignment where it is force*distance.ardupilot/libraries/SITL/SIM_Plane.cpp
Line 210 in e2767f8
However,
rot_accel
which is actually a torque is used to directly update the simulation dynamics https://github.com/ArduPilot/ardupilot/blob/2a218221f06b7ec5b6bb78ed82fdcf35c4db1e32/libraries/SITL/SIM_Plane.cpp#L397C5-L397C20.This is OK if we assume moment of inertia is
Vector3f moment_of_inertia = {1.0, 1.0, 1.0};
.Where this becomes an issue is in QuadPlane if a user wanted to get the moments of inertia used in the copter simulation.
https://github.com/ArduPilot/ardupilot/blob/2a218221f06b7ec5b6bb78ed82fdcf35c4db1e32/libraries/SITL/SIM_Frame.cpp#L572C1-L575C56
This has been corrected there where the variable reflects that it is a torque. #20529
Note
Unfortunately, dividing the plane rotational acceleration by the copter moments of inertia makes the quadplane sim unflyable.
Version
Went through the code on master and it looks like there are no plane moment of inertias. It's possible I'm missing it. It looks like the other sims do this.
Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ x ] Plane
[ ] Rover
[ ] Submarine
Airframe type
QuadPlane
Hardware type
SITL
Logs
Not applicable.
The text was updated successfully, but these errors were encountered: