jsbsim
jsbsim copied to clipboard
Propeller, engine improvements to support quadcopters etc.
I've been looking to model small quadcopters along the lines of the DJI Phantom plus hybrid models like the Wingcopter and the Alti.
I did a bit of JSBSim work for VTOL Technologies a couple of years ago and Marta Marimon mentioned that:
We used the external forces and moments to model the rotors.
Basically, our main limitation was the thrust-vectoring. As far as I remember, at that point in time, it was not possible to change the direction of the thrust vector (engine tilt) using the built-in model. This was our main reason for making use of the external forces and moments.
The second reason was that we had our own tool to compute the rotors thrust. Due to thrust-vectoring and the A/C flight envelope, the rotor(s) thrust was not only function of RPM/Power, but also the vehicle TAS and the tilt angle of the rotor(s). Therefore, the built-in model was not compatible since was not initially conceived for this type of propulsion.
As mentioned in the video you shared with me, the limitation of the built-in thrust/torque model was not a limitation at the end. Thanks to the flexibility of the external forces and moments capability and the way the configuration files are created, enabling different means to input data (equations, 3D tables, etc.), our ‘problem’ could be solved. Such flexibility is one of the advantages of JSBSim I believe. However, in the future it could be interesting to expand the built-in thrust/torque model and add a capability for drone propulsion, as more and more companies within the drone development use JSBSim.
Another thing I vaguely remember was that we had to slightly modify the workflow of the execution of the different JSBSim modules, since, for us, the external forces and moments had the dependency of AOA, BETA…
I came across a presentation by Matt Vacanti (@mvacanti) and Jesse Hoskins - Open Source Workflow for Advanced Vehicle Dynamics Simulation which included the following slide:
So I asked Matt Vacanti to elaborate on what the core assumptions are that break down when dealing with small UAS models in JSBSim.
A key point of clarification is that the issue is most pronounced when using the propeller / engine combination in a vertical lift scenario.
I ran into several problems and will dig up my old models to grab the gritty details but the problem is linked primarily to two issues:
JSBSim overrides the user entered moment of inertia for the propeller if it is less than 0.001 SLUG*FT2 so that it is always 0.001. This can be orders of magnitude too large for small propellers.
When using a jsbsim electric engine model, power is assumed to be linear to throttle input and torque is derived.
The combination of the two factors results in thrust and torque generation that significantly lags input commands (and also real world performance). This makes a small multicopter vehicle (vertical lift) completely unstable.
I settled on the lookup table solution as I felt the likely use case for someone interested matching real-world performance would be to measure actual system performance and apply coefficients as appropriate. There is a great wealth of small propeller data here: https://www.apcprop.com/technical-information/ which is where I extracted data for some of the models. The models I made publicly available are intentionally simple to make it easier for those picking it up to understand what is happening.
If I were to create a new function for small vertical lift motors / props I think it would need to have several considerations:
- Battery Voltage / Current Capacity (and therefore a battery model)
- User defined Motor Power and Torque Curves
Taking an initial glance at the source code for FGPropeller
I noticed in addition to the issue with propeller inertia being limited to a minimum of 0.001 SLUG*FT2 that Matt mentioned:
https://github.com/JSBSim-Team/jsbsim/blob/4fe1aa72cd4234824f686b9495194f2ef5556774/src/models/propulsion/FGPropeller.cpp#L78
I also noticed the following:
https://github.com/JSBSim-Team/jsbsim/blob/4fe1aa72cd4234824f686b9495194f2ef5556774/src/models/propulsion/FGPropeller.cpp#L53-L56
So the x-axis assumption is going to be an issue:
https://github.com/JSBSim-Team/jsbsim/blob/4fe1aa72cd4234824f686b9495194f2ef5556774/src/models/propulsion/FGPropeller.cpp#L270
https://github.com/JSBSim-Team/jsbsim/blob/4fe1aa72cd4234824f686b9495194f2ef5556774/src/models/propulsion/FGPropeller.cpp#L357
https://github.com/JSBSim-Team/jsbsim/blob/4fe1aa72cd4234824f686b9495194f2ef5556774/src/models/propulsion/FGPropeller.cpp#L211
There are quite a number of interesting topics that you are bringing up here 😄
Direction of the propeller axis
Regarding the propeller axis that is limited to the X-axis, you have to keep in mind that FGPropeller
inherits from FGThruster
.
FGThruster
allows to set an arbitrary frame transformation to propellers and nozzles using the element <orient>
(lines 95-98 below). And in addition the X direction can also be modified later in the simulation with the properties propulsion/engine[*]/pitch-angle-rad
and propulsion/engine[*]/yaw-angle-rad
(lines 99-102):
https://github.com/JSBSim-Team/jsbsim/blob/966098628f1b721ed1fd9926bdbd6e09b3f20b76/src/models/propulsion/FGThruster.cpp#L95-L102
So yes, computations are limited to the X-direction in the FGPropeller
class but there is a frame transformation prior to that. And this frame transformation can be rigged at any time during the simulation by the user. It is for that reason that the air velocity vector is transformed from the body frame to the propeller frame at the very beginning of the method FGPropeller::Calculate
(line 208):
https://github.com/JSBSim-Team/jsbsim/blob/966098628f1b721ed1fd9926bdbd6e09b3f20b76/src/models/propulsion/FGPropeller.cpp#L206-L208
As far as I know, the <orient>
feature is mainly used to model the fact that propeller engines are generally tilted by a few degrees with respect to the aircraft X axis in some aircraft such as for the P-51D. I guess these values are chosen by the aircraft manufacturer to account for installation effects (aerodynamic interaction between the propeller air flow and the fuselage and wings as well as compensation of the aircraft incidence in cruise conditions).
https://github.com/JSBSim-Team/jsbsim/blob/966098628f1b721ed1fd9926bdbd6e09b3f20b76/aircraft/p51d/p51d.xml#L413-L426
The properties propulsion/engine[*]/pitch-angle-rad
and propulsion/engine[*]/yaw-angle-rad
are typically used by rockets model in closed loop control of the nozzle orientation
https://github.com/JSBSim-Team/jsbsim/blob/966098628f1b721ed1fd9926bdbd6e09b3f20b76/aircraft/J246/Systems/J246FirstStageEffectors.xml#L32-L44
It must also be noted that the modifications of the propeller thrust direction, if any, are assumed to take place at a very slow pace. Otherwise, the rotational velocities should be taken into account to compute the gyroscopic moment ; something that neither FGThruster
nor FGPropeller
are capable of at the moment.
Propeller inertia lower limit
It is very likely that the lower limit 0.001 has been implemented to avoid null inertia which would obviously result in NaNs. In all likelihood, this value has been chosen arbitrarily and can be modified to a lower value as long as it is not zero.
Caution should be taken however about the size of the time step when very small inertias and masses are used. Historically, JSBSim has been designed for general aviation, civil and military aircraft and rockets. For such applications, the default time step of 120 Hz is generally a good choice. However for quadcopters, the time step might need to be chosen in the 1000 Hz so that the simulation produces plausible results.
Electric motors
Indeed, JSBSim model of electric motor is extremely simplistic. In addition to the limitations that @mvacanti mentioned, there are also the following ones (and most likely some others):
- There is an upper limit to the current that can be extracted from the batteries and that should place an upper limit on the power and torque of the engine
- Even though an electric engine as a very good efficiency, it is not 100% but rather in the 90% (the rest is mostly dissipated in heat by the Joule effect).
Pull requests are welcome ! 😄
Power transmission between propeller and engine
A topic that you did not mention but which is nonetheless a limitation of JSBSim propellers: the power transmission is one way, meaning that the engine drives the propeller but nothing can be transmitted from the propeller to the engine. This prevents windmilling and restart to be modelled for propeller engines and it also prevents autorotation to be modelled for copters.
Regarding the implications of the last topic I mentioned above, @jonsberndt wrote an interesting use case about an engine out failure on a twin engine aircraft C310.
Pull requests are welcome
Will do, just getting more familiar with the code first.
However for quadcopters, the time step might need to be chosen in the 1000 Hz so that the simulation produces plausible results.
I had noticed that AirSim uses 1KHz for their physics engine and the PX4 SITL - JSBSim bridge defaults to 250Hz.
I've updated the allowable minimum propeller inertia to 1e-6 slugft2 from the current 1e-3 slugft2.
The original value of 0.001 seemed potentially a bit arbitrary since both the minimum propeller diameter in feet was also set to 0.001 and so is the minimum gear ratio.
In Aircraft Control and Simulation (Stevens & Lewis) 3rd edition they have a small (2.8lb) quadrotor model and list the propeller's inertia as 3e-5 slug*ft2.
Also came across an inertia value of 4.46e-5 for DJI Z-blade 9450 propellers.
So I've set the minimum allowable inertia value 1 order of magnitude smaller at 1e-6.
Pushed. Thanks !
@mvacanti has been busy implementing a new electric engine model and testing it with small UAS models, take a look at his detailed report -
https://github.com/mvacanti/jsbsim/blob/pr-bldc-validation/SUAS_BLDC.md
@rega0051 have you tested out your F450 model after I made the change to allowable minimum propeller inertia, see - https://github.com/JSBSim-Team/jsbsim/issues/253#issuecomment-714731927
I'll be interested to compare the difference in performance of the F450 when used with @mvacanti's changes. I'm guessing the massive vertical acceleration I was seeing with the F450 model after I enabled the use of the supplied propeller's inertia is due to the massive RPM spike that @mvacanti mentions in his report.
@mvacanti I did a quick check with my F450 model and your BLDC_validation build. It seems to work fine. I had temporarily put an actuator model in for the ESC to slow down the response to work with reduced prop inertia (v1.1+).
I had to stare at the write-up and code for a good long while before I could follow along. I think the 'torqueconstant' parameter has a misleading name, and cause me a lot of confusion. I'd suggest not even having 'torqueconstant' as an input, the value in the examples is really just a combination of several conversion factors (peak-peak Volts -> RMS, RPM -> rad/s, Netwons -> Lbs, meters -> feet). Ideally, with no losses, k_V and k_T would be the same. Instead, I think it would be good to have an efficiency as an input (that's the only reason I can think of that I would change the 'torqueconstant' value as it was defined anyway). Then internally compute k_T, defined in a more conventional way:
RPM = Thruster->GetEngineRPM();
Jxx = ((FGPropeller*)Thruster)->GetIxx();
Torque = ((FGPropeller*)Thruster)->GetTorque();
TorqueConstant = Efficiency * (3.0/2.0) * 1.0/sqrt(3.0) * (1.0 / (VelocityConstant * rpmtoradpsec)) * newtontopound * metertofeet;
V = MaxVolts * in.ThrottlePos[EngineNumber];
CommandedRPM = V * VelocityConstant;
DeltaRPM = round(CommandedRPM - RPM);
TorqueRequired = abs(Torque);
CurrentRequired = TorqueRequired / TorqueConstant;
TorqueAvailable = (TorqueConstant * MaxCurrent) - TorqueRequired;
DeltaTorque = Jxx * (DeltaRPM * rpmtoradpsec) / max(0.00001, in.TotalDeltaT);
@seanmcleod the changes in the BLDC model include introduction of a new lever arm in the prop model. I thought the prop forces and moments were applied to the body correctly given the prop location and orientation. I thought the only thing that may be considered missing was if the rotor moved wrt the body frame.
changes in the BLDC model include introduction of a new lever arm in the prop model
Yep I noticed that. Busy having a look at the references he mentioned in the report and the current JSBSim code.
@mvacanti, @rega0051, @bcoconni I haven't worked on any of the JSBSim propeller code in the past, so I'm not that familiar with it, so there may be something I'm missing, but here is my review of the code to try and understand why @mvacanti felt the need to include a new lever arm into the calculations.
Current JSBSim application of the propeller torque on the airframe does not take into consideration the location of the prop (lever arm) as described by BOUABDALLAH, MURRIERI, and SIEGWART here....
I assume the reference is to this?
Where the torque around the x and y axis is simply the difference in thrust times the moment arm l.
And the torque around the z axis is the sum of the propeller torques.
Now the JSBSim code calculates the thrust of the propeller:
Thrust = ThrustCoeff*RPS*RPS*D4*rho;
vFn(eX) = Thrust;
Plus the torque:
PowerRequired = cPReq*local_RPS*local_RPS*local_RPS*D5*in.Density;
vTorque(eX) = -Sense*PowerRequired / (local_RPS*2.0*M_PI);
Plus the angular momentum for the gyroscopic effect:
FGColumnVector3 vH(Ixx*omega*Sense*Sense_multiplier, 0.0, 0.0);
Then the resultant moment combination of the gyroscopic effect and the propeller torque is calculated:
// Transform Torque and momentum first, as PQR is used in this
// equation and cannot be transformed itself.
vMn = in.PQRi*(Transform()*vH) + Transform()*vTorque;
Lastly the thruster's location relative to the cg will be used to generate an additional moment based on it's thrust. FGPropeller inherits from FGThruster which inherits from FGForce.
FGColumnVector3& FGForce::GetBodyForces(void)
{
vFb = Transform()*vFn;
// Find the distance from this vector's acting location to the cg; this
// needs to be done like this to convert from structural to body coords.
// CG and RP values are in inches
vDXYZ = fdmex->GetMassBalance()->StructuralToBody(vActingXYZn);
vM = vMn + vDXYZ*vFb;
return vFb;
}
Now @mvacanti's proposed changes includes a new lever arm which is used in 2 places, multiplying the propeller torque by it and the angular momentum by it.
vTorque(eX) = (-Sense*PowerRequired / (local_RPS*2.0*M_PI)) * TorqueLeverArm;
FGColumnVector3 vH(Ixx*omega*Sense*Sense_multiplier*TorqueLeverArm, 0.0, 0.0);
@mvacanti I don't really follow the logic and reasoning for this new lever arm.
@seanmcleod I have not yet read the document that @mvacanti wrote but I plan to.
I am in complete agreement with your analysis of the computation of the force and torques generated by a propeller. The lever arm between the propeller and the CG is indeed accounted for by JSBSim via the FGForce
class.
@seanmcleod @bcoconni @rega0051 Thank you for the feedback and support. I have validated the F450 with the same BLDC model and published the configuration here.
The results from the JSBSim PX4 Bridge Simulation for the F450 using the same environment etc as the earlier write-up are similarly successful as the hexacopter:
@rega0051 please take a look at the modifications I made to the F450 model and let me know how that compares against the version you flew.
@seanmcleod I agree that the lever arm should not be required. However, I have not been able to prove that the FGForce class is actually doing what we expect. I will devise a test to validate. Will be back shortly with more assessment.
I have produced a validation that I believe demonstrates the FGForce class is not behaving as expected (also updated in the earlier documentation):
Configuration | Setting |
---|---|
Environment | px4_jsbsim_docker |
PX4 | https://github.com/PX4/PX4-Autopilot.git |
-- Branch | master |
-- Revision | 5d7ea62190bf6b64263fb53d3b1515bb0757a44b |
JSBSim | https://github.com/mvacanti/jsbsim.git |
-- Branch | pr-bldc-validation |
-- Revision | fb7de0a093f0c9da084bd97229d15e013ca0a6bd |
JSBSim Bridge | https://github.com/mvacanti/px4-jsbsim-bridge.git |
-- Branch | pr-jsbsim-bldc |
-- Revision | e89153756262de9edc31040b843c4e859d89b301 |
-- Aircraft | hexarotor_x |
-- Engine | DJI-3510-380 |
-- Propeller | APC_13x8E_8K |
-- Torque | Baseline |
Flight Plan | yaw_test.plan |
The results of completing the flight plan above (climb to altitude then yaw to a heading) produces a .csv file that includes the following data:
- JSBSim standard Moments
- JSBSim standard Forces
- Torque produced by the propeller here.
Given BOUABDALLAH, MURRIERI, and SIEGWART (p. 175 (5)) we would expect that the Total N moment calculated by JSBSim (absent other external forces) to equal the sum all propeller torque multiplied by the distance of the propeller to the center of gravity (C.G.). In the case of the hexarotor_x this distance is 2.53 Ft or 0.772M.
Plotting the .csv file generate by JSBSim for this flight we observe that the Total N moment is equal to the sum of the
total propeller torque. This indicates that the distance of the propeller to the C.G. is not being applied.
expect that the Total N moment calculated by JSBSim (absent other external forces) to equal the sum all propeller torque multiplied by the distance of the propeller to the center of gravity (C.G.).
Why do you expect there to be a lever arm for this? The total N moment is the last entry in the following vector and there is no moment arm for it, unlike for the 1st two entries.
I agree with Sean, here. Torque is torque, and there is no moment arm to be applied. Unless I am missing something.
Jon
@mvacanti
we would expect that the Total N moment calculated by JSBSim (absent other external forces) to equal the sum all propeller torque multiplied by the distance of the propeller to the center of gravity (C.G.).
My teachers in physics always told me "Check your units !". So if I read correctly your statement above, then it cannot be correct: a torque is expressed in N.m (i.e. a force multiplied by a distance), a distance is expressed in meters and a moment in N.m so there is no way you can sum torques multiplied by a distance (units: N.m^2) and get a moment (units: N.m)
@seanmcleod @jonsberndt @bcoconni Thank you, all fair feedback and inputs.
Here is where I am really stuck:
The performance of the vehicle in yaw without this "multiple" of torque is unstable. Applying the multiple I have described instantly makes the vehicle perform "realistically" hence how I went down this rabbit hole. This could be caused by:
- Control Laws
- Calculation of Propeller Torque
What bothers me is that the appearance of performance is not off by a little, it is off by more than >2x in the case of the hexarotor example.
I will keep digging.
@mvacanti if you're confident the Cp is correct or close enough what about the moment of inertia of the drone, maybe it's off by a factor of 2 or so?
My guess is Propeller Torque. The sim assumes that all the mechanical power produces Thrust, via the CP and CT values. The leftover power is all assumed to generate torque. Effectively, CQ = CP/(2*pi). This a fairly good assumption for a prop aircraft operating near its design condition. The static condition is only momentarily encountered; in the multicopter case the prop is nearly always operating near the static condition.
The traditional definition of prop efficiency would be: eff = CT * J / CP. We really want: eff = (CT * J + CQ * n) / CP. With this definition power loss would only be associated with acoustics, heat, turbulence, etc.
I pulled the APC dataset for the 9X4.5E at n= 2000 RPM. V = 0 mph J = 0 Efficiency = 0 (ill-defined, clearly thrust is generated from the power) Ct = 0.1157 Cp = 0.469 Pwr = 13.2 in lbf/s (sorry, units are horrible; and it looks like Pwr is computed from CP with a significant loss in precision) Torque = 0.056 in-lbf Thrust = 0.097 lbf
Looking at the power usage in this condition: PwrTorque = Torque * n = 0.056 in-lbf * 133 (rad / s) = 7.5 (in lbf / s) PwrThrust = Thrust * Vinduced = 0.097 lbf * 33.2 (in / s) = 3.2 (in lbf / s)
So, about 20% of the power is lost to the ether. There is a lot of ugly rounding and loss of precision due to the database though. Unfortunately, they don't provide the torque coefficient directly. I believe the code, as it exists now, would have put 100% of the power to torque generation in the form of prop acceleration; but if 13.2 of power were available we should really be steady-state (APC data is steady-state).
I think the approach should be to modify FGPropeller.c to use a C_Torque table (if provided) to compute the power required for the steady state thrust and torque, then compute the remaining power available for acceleration. Backward compatibility can be maintained by retaining the existing algorithm if a C_Torque table is not provided.
@rega0051
The traditional definition of prop efficiency would be: eff = CT * J / CP. We really want: eff = (CT * J + CQ * n) / CP. With this definition power loss would only be associated with acoustics, heat, turbulence, etc.
I may be wrong but CP and CQ are really 2 sides of the same coin which means that the relationship
$$C_P=2\pi C_Q$$
Furthermore, the relationship you suggest for the efficiency does not stand because you did not check your units :smile:
$$\eta=\frac{C_T J+C_Qn}{C_P}$$
$C_T$, $C_P$, $C_Q$ and $J$ are dimensionless while n has the dimension of rotations per second or s^-1 so you cannot add $C_T J$ to $C_Q n$.
PwrThrust = Thrust * Vinduced = 0.097 lbf * 33.2 (in / s) = 3.2 (in lbf / s)
Where do you get this relationship from ? Froude's momentum theory states that an hovering rotor produces no thrust power even though the velocity through the propeller (V induced) is non zero.
I think the approach should be to modify FGPropeller.c to use a C_Torque table (if provided) to compute the power required for the steady state thrust and torque, then compute the remaining power available for acceleration.
As I mentioned above I think this table would be redundant with C_POWER
as C_TORQUE
could be trivially obtained by dividing the table C_POWER
by 2π
My efficiency equation was intended as illustration, as you point out the units don't work. Sloppy, sorry. I wasn't advocating to redefine prop efficiency. The point was to highlight that efficiency only includes Thrust, but for multi-copters the torque component is essential for control.
The approach in FGPropeller may no longer represent a set of good assumptions. We're using data that wasn't generated based on conservation-based approaches. In particular, in the static case it seems to be significantly different (this isn't surprising to me at all). Which is where multi-copters operate, which may help explain why @mvacanti is having stability issues. If that dataset is broadly representative it could result in a significant difference in control sensitivity, particularly in yaw.
I used: Thrust * Vinduced to estimate a power value for the axial flow, I think that's reasonable. I can only imagine that the statement about Froude's momentum conservation in hover is a consequence of defining advance ratio with the free-stream velocity rather than using the total velocity at the rotor disk. It's far more convenient to use the free-stream velocity, but it does make the static condition ill-defined. Clearly power is used to produce static thrust!
@mvacanti in your original email to me you mentioned making use of measured data from rcbenchmark using their propeller test stands. In your report you compared the JSBSim calculated data to data from http://www.flybrushless.com/ and https://www.ecalc.ch/motorcalc.php however I noticed that they don't report torque data.
So we should be able to compare the JSBSim calculated toque, assuming a matching propeller etc., with some ground truth torque data from rcbenchmak, e.g. https://database.rcbenchmark.com/tests/qzy/multistar-elite-2306-2150kv-gemfan-6030r
I have just re-read Stevens & Lewis' "Aircraft Control and Simulation (3rd edition)" especially the chapter 8.2 "Propeller/Rotor Forces and Moments". If I am not mistaken, it seems that JSBSim has at least 2 things wrong regarding propellers generated forces and moments.
Torque applied on the aircraft by the propeller
On figure 8.2-1 Stevens & Lewis show how the various torques add or subtract to influence the propeller and aircraft motions.
It should be noticed in particular that it is the torque generated by the motor that is affecting the aircraft motion (see the red arrow below):
However, in JSBSim, the torque is computed from the propeller aerodynamics.
First, the propeller power is computed from the C_POWER
table:
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/models/propulsion/FGPropeller.cpp#L294
then the torque is obtained by dividing the power by the propeller angular rate
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/models/propulsion/FGPropeller.cpp#L351-L352
and finally the torque is added to the aircraft moments (after being transformed from the propeller frame to the body frame)
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/models/propulsion/FGPropeller.cpp#L280-L282
So what is implemented in JSBSim is the red arrow below:
As long as the propeller RPM is constant this does not make any difference. However, when the propeller accelerates or decelerates it does make a difference since we are underestimating the torque applied on the aircraft when accelerating (resp. overestimating it when decelerating).
According to that, I think that the torque vTorque
should be computed from the engine power EnginePower
:
--- a/src/models/propulsion/FGPropeller.cpp
+++ b/src/models/propulsion/FGPropeller.cpp
@@ -277,6 +277,8 @@ double FGPropeller::Calculate(double EnginePower)
if (RPM < 0.0) RPM = 0.0; // Engine won't turn backwards
+ vTorque(eX) = -Sense*EnginePower / (max(0.01, RPS)*2.0*M_PI);
+
// Transform Torque and momentum first, as PQR is used in this
// equation and cannot be transformed itself.
vMn = in.PQRi*(Transform()*vH) + Transform()*vTorque;
@@ -349,7 +351,6 @@ double FGPropeller::GetPowerRequired(void)
double local_RPS = RPS < 0.01 ? 0.01 : RPS;
PowerRequired = cPReq*local_RPS*local_RPS*local_RPS*D5*in.Density;
- vTorque(eX) = -Sense*PowerRequired / (local_RPS*2.0*M_PI);
return PowerRequired;
}
Air velocity in the propeller frame
Another strong assumption that JSBSim is making is that the aerodynamic velocity is uniform over the aircraft. In particular it means that the local air velocity at the propeller is not influenced by the position of the propeller. Strictly speaking this not true since air velocity is affected by the angular rates Pi, Qi, Ri of the aircraft relative to the inertial frame (eqn 8.2-1 in Steven & Lewis):
$$v_{rel}^P=v_{rel}^b+\omega_{b/i}^b\times p^b_{P/CM}$$ where:
- $v_{rel}^P$ is the propeller air velocity
- $v_{rel}^b$ is the air velocity at the aircraft CG
- $\omega_{b/i}^b$ is the aircraft angular rates (coordinates Pi, Qi, Ri) with respect to the inertial frame
- $p^b_{P/CM}$ is the position of the propeller with respect to the aircraft CG expressed in the body frame.
However, in JSBSim, the air velocity is obtained from FGAuxiliary
:
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/FGFDMExec.cpp#L513-L514
then transferred to the thruster by FGEngine
(the member FGEngine::in
is a simple reference to FGPropulsion::in
)
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/models/propulsion/FGEngine.cpp#L149-L155
and finally used by FGPropeller
after a simple transformation from the body frame to the propeller frame:
https://github.com/JSBSim-Team/jsbsim/blob/05bd64aaaaaf32ab816bec0fa4b4df4a0e5c97c6/src/models/propulsion/FGPropeller.cpp#L201-L206
It is therefore obvious that the term $\omega_{b/i}^b\times p^b_{P/CM}$ is ignored.
Fortunately that should not make much difference for an aircraft for which the angular rates Pi, Qi and Ri are small. However this might not be true for a small quadcopter that is capable of much higher angular rates due to its small inertia.
So in order to account for the $\omega_{b/i}^b\times p^b_{P/CM}$ term, the computation of the local air velocity should be modified:
--- a/src/models/propulsion/FGPropeller.cpp
+++ b/src/models/propulsion/FGPropeller.cpp
@@ -41,6 +41,7 @@ INCLUDES
#include "FGFDMExec.h"
#include "FGPropeller.h"
#include "input_output/FGXMLElement.h"
+#include "models/FGMassBalance.h"
using namespace std;
@@ -200,7 +201,8 @@ void FGPropeller::ResetToIC(void)
double FGPropeller::Calculate(double EnginePower)
{
- FGColumnVector3 localAeroVel = Transform().Transposed() * in.AeroUVW;
+ FGColumnVector3 vDXYZ = fdmex->GetMassBalance()->StructuralToBody(vActingXYZn);
+ FGColumnVector3 localAeroVel = Transform().Transposed() * (in.AeroUVW + in.PQRi*vDXYZ);
double omega, PowerAvailable;
double Vel = localAeroVel(eU);
Strictly speaking the turbulence in.AeroPQR
should be subtracted from in.PQRi
but we will leave that apart for a start.
Let me know what you all think.
@rega0051
The approach in FGPropeller may no longer represent a set of good assumptions. We're using data that wasn't generated based on conservation-based approaches. In particular, in the static case it seems to be significantly different (this isn't surprising to me at all). Which is where multi-copters operate, which may help explain why @mvacanti is having stability issues. If that dataset is broadly representative it could result in a significant difference in control sensitivity, particularly in yaw.
Which assumptions are you referring to ? Could you be more specific ? In particular, I don't understand what you mean by "We're using data that wasn't generated based on conservation-based approaches." What do you call conservation-based approaches ?
I used: Thrust * Vinduced to estimate a power value for the axial flow, I think that's reasonable. I can only imagine that the statement about Froude's momentum conservation in hover is a consequence of defining advance ratio with the free-stream velocity rather than using the total velocity at the rotor disk. It's far more convenient to use the free-stream velocity, but it does make the static condition ill-defined. Clearly power is used to produce static thrust!
Forget what I said: it was rubbish. Froude's momentum theory indeed finds that a propeller produces/consumes power even while hovering. Actually, in most cases the power produced by a propeller is determined by the effect it has on the aircraft velocity (Thrust*Velocity) but it can also be determined by the effect it has on air: it pushes air down to produce thrust.
More rubbish
[EDIT] I am pretty sure something is flawed in the reasoning below.
The thrust is equal to the difference of the momentum of air between the stream tube inlet and the stream tube outlet:
$$T=\dot{m}(V_T^P+2v_i-V_T^P)=\dot{m}2v_i$$
The work on the air flow upstream of the propeller during a time interval dt is:
$$W_1=\dot{m}V_T^P\times (V_T^Pdt)=\dot{m}{V_T^P}^2dt$$
The work on the air flow downstream of the propeller during a time interval dt is:
$$W_2=\dot{m}(V_T^P+2v_i)\times (V_T^P+2v_i)dt=\dot{m}(V_T^P+2v_i)^2dt$$
So the power produced by the propeller is
$$P=\frac{W_2-W_1}{dt}=\dot{m}\left[(V_T^P+2v_i)^2-{V_T^P}^2\right]=\dot{m}2v_i(2V_T^P+2v_i)$$
or
$$P=2T(V_T^P+v_i)$$
For a hovering propeller we have $V_T^P=0$ and thus $P=2Tv_i$.
Let me know what you all think.
I read chapter 8 of Stevens & Lewis and agree with your observations in terms of the toque applied to the aircraft and the air velocity in the propeller frame.
In terms @mvacanti's issue with too small an N moment during the yaw the combination of underestimating the torque on the aircraft during RPM acceleration and overestimating when the RPM is decelerating means they'll more than likely roughly cancel out since half the propellers will be accelerating and half will be decelerating to produce the yawing moment, i.e. we won't see a ~2x increase in the N moment.
In terms @mvacanti's issue with too small an N moment during the yaw the combination of underestimating the torque on the aircraft during RPM acceleration and overestimating when the RPM is decelerating means they'll more than likely roughly cancel out since half the propellers will be accelerating and half will be decelerating to produce the yawing moment, i.e. we won't see a ~2x increase in the N moment.
On the contrary, since the yawing moment is obtained by say decreasing power of clockwise rotating propellers and increasing power of counterclockwise propellers then the variation of each rotor will add up (since we are subtracting values of opposite sign). This may or may not fix the problem reported by @mvacanti but the effect will definitely not cancel out.
I read chapter 8 of Stevens & Lewis and agree with your observations in terms of the toque applied to the aircraft and the air velocity in the propeller frame.
Great ! These modifications are now implemented in the master
branch (commit 22f8330).
On the contrary, since the yawing moment is....
You're right, I wasn't thinking straight in terms of the signs 😉
@seanmcleod and @bcoconni Thanks for the great discourse and updates. I will pull the commit and report back on the performance. I have begun investigating how it may be possible to use open source real world vehicle log data as a reference for validation purposes as well.
@mvacanti when I took at https://www.rcbenchmark.com/ I couldn't find any tests using APC propellers in terms of trying to get some ground truth data for torque.