JSBSim-Team / jsbsim

An open source flight dynamics & control software library
GNU Lesser General Public License v2.1
1.26k stars 431 forks source link

Propeller, engine improvements to support quadcopters etc. #333

Open seanmcleod opened 3 years ago

seanmcleod commented 3 years ago

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:

image

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:

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

  2. 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:

  1. Battery Voltage / Current Capacity (and therefore a battery model)
  2. 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

bcoconni commented 3 years ago

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

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.

bcoconni commented 3 years ago

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.

seanmcleod commented 3 years ago

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.

seanmcleod commented 3 years ago

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.

bcoconni commented 3 years ago

Pushed. Thanks !

seanmcleod commented 3 years ago

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

rega0051 commented 3 years ago

@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);
rega0051 commented 3 years ago

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

seanmcleod commented 3 years ago

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.

seanmcleod commented 3 years ago

@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?

image

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.

bcoconni commented 3 years ago

@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 FGForceclass.

mvacanti commented 3 years ago

@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:

2020-11-30_21-50-40_01_plot

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

mvacanti commented 3 years ago

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:

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

seanmcleod commented 3 years ago

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.

image

jonsberndt commented 3 years ago

I agree with Sean, here. Torque is torque, and there is no moment arm to be applied. Unless I am missing something.

Jon

bcoconni commented 3 years ago

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

mvacanti commented 3 years ago

@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:

  1. Control Laws
  2. 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.

seanmcleod commented 3 years ago

@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?

rega0051 commented 3 years ago

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.

bcoconni commented 3 years ago

@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π

rega0051 commented 3 years ago

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!

seanmcleod commented 3 years ago

@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

bcoconni commented 3 years ago

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. Figure 8.2-1 Stevens & Lewis 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): Figure 8.2-1 Stevens & Lewis - Engine power 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: Figure 8.2-1 Stevens & Lewis - Propeller power 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:

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.

bcoconni commented 3 years ago

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

Propeller momentum theory

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

seanmcleod commented 3 years ago

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.

bcoconni commented 3 years ago

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.

bcoconni commented 3 years ago

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

seanmcleod commented 3 years ago

On the contrary, since the yawing moment is....

You're right, I wasn't thinking straight in terms of the signs 😉

mvacanti commented 3 years ago

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

seanmcleod commented 3 years ago

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

bcoconni commented 3 years ago

I completely forgot to mention that JSBSim computation of the sign of the gyroscopic effect has been erroneous until April 2015 and has been fixed in the commits 6b7a2103bc8b47c62c8bab17fbe7 and efef744d4c7ef8c946f185add3

Since this bug has existed for a long time, it has been decided to fix the problem by adding a version attribute to the propeller section of the aircraft XML definition. When the version attribute is specified to a value strictly higher than 1.0, JSBSim computes the correct sign of the gyroscopic effect. Otherwise JSBSim uses the historical erroneous sign for the gyroscopic moment.

<propeller name="xyz" version="1.01">
  <!-- Propeller definition goes here -->
</propeller>

So it is strongly recommended to specify the version attribute to the propeller definition so that the correct sign of the gyroscopic effect is used.

rega0051 commented 3 years ago

I made a PR in my fork: https://github.com/rega0051/jsbsim/pull/1

I'm more accustomed to a different FDM system, so I hadn't fully realized how the motor and prop models were coupled in JSBSim, I had a weird mixed interpretation a few months ago. I can't even decipher some of the things I said. So, I started a fresh look.

I started with what @mvacanti had provided for the BLDC, and reduced it down a lot. The characteristic that I desire is that of a first-order system, so rather that use a feed forward like command and torque limits, I instead put the first-order lag on the values from the Prop model; so the RPM measured is filtered. Since I really only care about the response of the system (not interested in modeling the motor controller itself) it seems reasonable to just treat the closed-loop response of the system as first-order with a user supplied time constant, tau.

With these goals in mind it seemed reasonable to change FGElectric. I added two XML parameters; maxrpm and tau. If maxrpm > 0, then the input command is treated as a proportion of maxrpm and prop RPM is the feedback. If maxrpm == 0, then max power is the scaling factor, and prop power required is the feedback. The other parameter, tau, sets the time constant of the first-order filter on feedback; whether its prop RPM or power required. Backward compatibility is preserved if neither maxrpm or tau are set.

I tweaked my F450 model to use the changes. The flight control has the same inner-loop PID gains as PX4, so it should be fairly representative of the close-loop system (minus transport delays). I set the maxrpm to 16000, which is kV max voltage (960 RPM/Volt 16.8 Volt). I set tau to 0.100 sec, which is roughly what I've seen in bench tests (it could be anywhere from 0.050 sec to 0.150 sec, want to test specifically for bandwidth after pandemic).

F450: https://github.com/UASLab/OpenFlightSim/tree/master/Simulation/aircraft/F450 Motor Model: https://github.com/UASLab/OpenFlightSim/blob/master/Simulation/engine/DJI_E305.xml Test Script: https://github.com/UASLab/OpenFlightSim/blob/master/Simulation/scripts/Test_F450_Launch.xml

I still don't have a nice PX4 setup yet so if @mvacanti could check it out I'd be appreciative. I also want to mimic that "hold-down" bench check.

bcoconni commented 3 years ago

@rega0051

The characteristic that I desire is that of a first-order system, so rather that use a feed forward like command and torque limits, I instead put the first-order lag on the values from the Prop model; so the RPM measured is filtered. Since I really only care about the response of the system (not interested in modeling the motor controller itself) it seems reasonable to just treat the closed-loop response of the system as first-order with a user supplied time constant, tau.

I am not very fond of these kind of C++ hardcoded phenomenological models. We already have this kind of model for FGTurbine and what we have ended up with are lots of PR from people asking for being able to tweak the model to their need (PR #121, #139, #188, #382, #387 - and that's only for the last 2 years) and we have plans for more (see discussion #389).

With these goals in mind it seemed reasonable to change FGElectric.

I don't think so. FGElectric is a trivial model: its power output is proportional to the throttle position. I am pretty sure you can use XML code to assign a first order lag of the throttle command and drive the engine power through the throttle position.

Most people underestimate the actual power of FGElectric because it's so trivial. But it's the only engine model in JSBSim that gives you the full control over your engine. You can theoretically code in XML any kind of motor/engine with FGElectric !

rega0051 commented 3 years ago

@bcoconni Phenomenological models are completely appropriate for flight dynamics models. That's what the whole sim is! The details to model a real motor requires parameters that are not readily knowable. For electric motor (actuators or for propulsion) we won't know the internal control system the controllers are using, nor should we need a slew of parametric values (motor velocity constant, inductance, resistance, controller capacitance, resistance, frame rate, gains, etc.). Knowing the response function should be adequate for a FDM.

The filter in feedback is not the same as a filter on the input. I previously had a FGActuator upstream of the motor command, and it does at least prevent the control system from using the infinite bandwidth of the motor. Is there another way to introduce limited bandwidth in the Prop and Motor interaction? The use of throttle position as speed command is tied to the feedback signal, which is why I ended up putting that in there as well. I think this is a reasonable incremental improvement.

bcoconni commented 3 years ago

Phenomenological models are completely appropriate for flight dynamics models. That's what the whole sim is! The details to model a real motor requires parameters that are not readily knowable. For electric motor (actuators or for propulsion) we won't know the internal control system the controllers are using, nor should we need a slew of parametric values (motor velocity constant, inductance, resistance, controller capacitance, resistance, frame rate, gains, etc.). Knowing the response function should be adequate for a FDM.

I think you misread my statement and missed the first 2 words in "C++ hardcoded phenomenological models". I never said phenomenological models should not be used in flight dynamics. I am saying such models should not be hardcoded in the C++ code of JSBSim. That's quite a different statement !

There are a lot of places in JSBSim where no assumption are made about the model including whether it is phenomenological or not. Aerodynamics is one such place where you can use, at your convenience, a linear relationship between lift and AoA or a very complex function that depends on a lot of parameters. I see no reason why this could not be the case for electric motors.

The filter in feedback is not the same as a filter on the input. I previously had a FGActuator upstream of the motor command, and it does at least prevent the control system from using the infinite bandwidth of the motor. Is there another way to introduce limited bandwidth in the Prop and Motor interaction? The use of throttle position as speed command is tied to the feedback signal, which is why I ended up putting that in there as well. I think this is a reasonable incremental improvement.

I may be missing something but I see no difference between your C++ code and the flight control system below (granted that the properties propulsion/engine[]/propeller-torque and propulsion/engine[]/propeller-power are missing at the moment - but this could be easily fixed). So I am struggling to see the distinction you are making between filter in feedback and filter on the input.

For better legibility, I have omitted the min/max computations to ensure that RPM is positive and lower than the max value maxRPM.

<system name="motor control">
  <property name="maxRPM"> 10000. </property>
  <property name="maxPOWER"> 10. </property>
  <channel name="motor bandwith">

    <!-- First order lag on RPM measure -->
    <lag_filter name="filtered-rpm">
      <input>propulsion/engine[0]/engine-rpm</input>
      <c1> 2.0 </c1> <!-- tau -->
    </lag_filter>

    <!-- Change in RPM -->
    <fcs_function>
      <function name="delta-rpm">
        <difference>
          <product>
            <property>fcs/throttle-cmd-norm[0]</property>
            <property>maxRPM</property>
          </product>
          <property>filtered-rpm</property>
        </difference>
      </function>
    </fcs_function>

    <!-- Power Command: DeltaPower = DeltaRPM * TorqueReq -->
    <fcs_function>
      <function name="cmd-power">
        <sum>
          <product>
            <property>propulsion/engine[0]/propeller-torque</property>
            <property>delta-rpm<property>
            <value>0.104719</value> <!-- rpm to rad/sec -->
          </product>
          <property>propulsion/engine[0]/propeller-power</property>
        </sum>
      </function>
    </fcs_function>

    <!-- Convert power command to throttle position -->
    <fcs_function>
      <function name="fcs/throttle-pos-norm[0]">
        <quotient>
          <property>cmd-power</property>
          <property>maxPOWER</property>
        </quotient>
      </function>
    </fcs_function>
  </channel>
</system>
rega0051 commented 3 years ago

@bcoconni The value for Tau isn't hard-coded. You have an issue with it just being first-order? I'd be happy with a FGFilter instance; but even FGFilter is hard-coded to some degree.

Input filtering is not the same as feedback filtering. Lets define the Motor model as K(s) (controller), Prop model as G(s) (plant) in feedback, the and a filter as F(s). The comp sensitivity function with F acting on the input is: T(s) = inv(1 + K(s)G(s))K(s)F(s); instability at K(s)G(s)=-1. With F(s) in the feedback T(s) = inv(1+K(s)G(s)F(s))K(s); instability at K(s)G(s)F(s)=-1.

There is also a case to be made that some damping in the numerics would be helpful. Right now there is no damping mechanism between the Prop and Motor, the bandwidth is limited only by the sim dt value. We've seen cases where the RPM jumps to huge values because of numeric sensitivity.

bcoconni commented 3 years ago

The value for Tau isn't hard-coded. You have an issue with it just being first-order? I'd be happy with a FGFilter instance; but even FGFilter is hard-coded to some degree.

I am obviously not making myself clear, sorry about that. What I am trying to explain is that you don't need to modify the C++ code of JSBSim for your purpose.

Whether you are using your own first order filter, FGFilter, FGActuator or any other control system that exists under the sun is irrelevant to the point I am trying to make. The XML code that I suggested above is the equivalent of your C++ code. I just tried to mimic the behaviour of your C++ code, no more no less. Whether or not a first order filter fits your purpose is you to tell, not me.

Once again, I am trying to show you that you can get your phenomenological model in your UAV FDM without altering the C++ code of JSBSim (except perhaps by adding 2 new properties propulsion/engine[]/propeller-torque and propulsion/engine[]/propeller-power that are currently not available)

The problem being that if a first order filter is coded in FGElectric then sooner or later someone will want to alter the C++ code to add, say a second order filter, etc. Fortunately we can already avoid this situation upfront because you (@rega0051) don't need to modify the C++ code of JSBSim to simulate your UAV motors with a first order filter.

Input filtering is not the same as feedback filtering. Lets define the Motor model as K(s) (controller), Prop model as G(s) (plant) in feedback, the and a filter as F(s). The comp sensitivity function with F acting on the input is: T(s) = inv(1 + K(s)G(s))K(s)F(s); instability at K(s)G(s)=-1. With F(s) in the feedback T(s) = inv(1+K(s)G(s)F(s))K(s); instability at K(s)G(s)F(s)=-1.

Thanks for the control theory refresher :+1: :smiley:

However my problem remains the same: there is no feedback from FGPropeller to FGElectric. Check the code by yourself: https://github.com/JSBSim-Team/jsbsim/blob/33d429e783589c27dccf2d70d231efe98c38f1df/src/models/propulsion/FGElectric.cpp#L86-L103 The motor power does not depend on any input from the propeller (see line 97) so there is no feedback and I don't see how your comment "Input filtering is not the same as feedback filtering" might be any relevant to the subject.

Or may be you did not see that there are two different properties of the controls : one for the command, one for the position ? FGElectric uses the throttle position as an input and the whole point of the XML code I made is to compute the throttle position fcs/throttle-pos-norm[0] from the throttle command fcs/throttle-cmd-norm[0] to drive the motor output power.

There is also a case to be made that some damping in the numerics would be helpful. Right now there is no damping mechanism between the Prop and Motor, the bandwidth is limited only by the sim dt value. We've seen cases where the RPM jumps to huge values because of numeric sensitivity

I'd like to see examples before jumping to the conclusion that numerical damping is needed.

rega0051 commented 3 years ago

The current state is that all multi-copter models that we've been able to find use External Forces rather than the Propulsion models. I'm just trying to address one of the issues that underlies that reality. I'm saying there should be feedback in that system. I thought a PR would be a good course of action. I'm also not implying that this PR will fix every inevitable issue, nor does it address all the issue that have been brought up in issue 333. I just felt it was a doable increment that preserved backward compatibility could be a nice thing. I believe it captures the characteristic that the proposed BLDC model obtained without requiring a step-wise dynamic inversion as feedback (https://github.com/mvacanti/jsbsim/blob/e6d58b2268c1609b15f362a04520eac9bb3321d5/src/models/propulsion/FGBldc.cpp#L104) and limits to regulate the response (https://github.com/mvacanti/jsbsim/blob/e6d58b2268c1609b15f362a04520eac9bb3321d5/src/models/propulsion/FGBldc.cpp#L106).

A spike in RPM is shown in the nice writeup that @mvacanti did: https://github.com/mvacanti/jsbsim/blob/pr-bldc-validation/SUAS_BLDC.md#propeller-and-engine-torque

bcoconni commented 3 years ago

I'm saying there should be feedback in that system.

Did I say otherwise ?

seanmcleod commented 3 years ago

@rega0051 do you agree or not that @bcoconni's XML example he provided matches/mimics your C++ code that you implemented in your PR?

If it does then he's saying that a JSBSim user wanting to model a multi-copter could use the existing FGElectric engine and make use of the XML code he's provided to get the same results as compared to using a modified FGElectric model along the lines of your PR.

So if that is the case then are you arguing it would be more convenient for a JSBSim user to make use of your modified FGElectric model and providing MaxRPM and tau in their engine file as opposed to including @bcoconni's XML snippet in their model?

rega0051 commented 3 years ago

@seanmcleod and @bcoconni on Monday I'll do a comparison and add a PR with the additional Get/Set methods. I'm guessing it will be equivalent, or could be made equivalent. I'd really like other folks who thinks they have a working multi-copter model to evaluate and compare as well.

Two lines in the motor definition is more convenient for me than replication of scripting, but I understand the maintenance issue as well. I do believe that all uses of FGElectric should be implementing a time constant or bandwidth limit in feedback (or there should be another relaxation parameter introduced to eliminate the huge RPM spike). And using external forces to mimic the propulsion system works as well... How do you decide were to draw the line on interfacing sub-systems? All options seem like an incomplete band-aide. I want to help, but not waste my time or everybody else's.

rega0051 commented 3 years ago

PR #394 exposes additional properties in FGPropeller: propulsion/engine[#]/propeller-power propulsion/engine[#]/propeller-torque propulsion/engine[#]/propeller-sense

An example of a F450 frame based quad copter is below, along with the required propulsion system definitions. The desired command to the ESC is proportional to the max RPM of the motor. Required propeller torque is used to provide an appropriate scale change from normalized RPM to normalized power for the motor (as required by FGElectric). Max power ends up being defined in two places, in the 'Effectors' system and in the 'electric_engine' below (max motor power could be exposed as a property in FGElectric to avoid replication). propeller sense (clockwise or counter-clockwise) is defined only in the propulsion defintion, and is pulled into the 'Effectors' systems below through exposing propeller-sense from FGPropeller.

<system name="Effectors">
    <property value="16000.0"> fcs/maxRPM </property> <!-- Max motor RPM -->
    <property value="320.0"> fcs/maxPwr_Watt </property> <!-- Max motor power -->
    <property value="20"> fcs/lagMotor </property> <!-- lag = tau_s / dt -->

  <channel name="Electronic Speed Conrollers">
    <!-- First order lag on RPM measure -->
    <lag_filter name="fcs/filtMeasFR_rpm">
      <input> propulsion/engine[0]/propeller-rpm </input>
      <c1> fcs/lagMotor </c1>
    </lag_filter>
    <lag_filter name="fcs/filtMeasAL_rpm">
      <input> propulsion/engine[1]/propeller-rpm </input>
      <c1> fcs/lagMotor </c1>
    </lag_filter>
    <lag_filter name="fcs/filtMeasFL_rpm">
      <input> propulsion/engine[2]/propeller-rpm </input>
      <c1> fcs/lagMotor </c1>
    </lag_filter>
    <lag_filter name="fcs/filtMeasAR_rpm">
      <input> propulsion/engine[3]/propeller-rpm </input>
      <c1> fcs/lagMotor </c1>
    </lag_filter>

    <!-- Change in RPM:
    deltaCmd_rpm = cmdEsc_nd * maxRPM + filtMeas_rpm -->
    <fcs_function>
      <function name="fcs/deltaCmdFR_rpm">
        <difference>
          <product>
            <property> fcs/cmdEscFR_nd </property>
            <property> fcs/maxRPM </property>
          </product>
          <property> fcs/filtMeasFR_rpm </property>
        </difference>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/deltaCmdAL_rpm">
        <difference>
          <product>
            <property> fcs/cmdEscAL_nd </property>
            <property> fcs/maxRPM </property>
          </product>
          <property> fcs/filtMeasAL_rpm </property>
        </difference>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/deltaCmdFL_rpm">
        <difference>
          <product>
            <property> fcs/cmdEscFL_nd </property>
            <property> fcs/maxRPM </property>
          </product>
          <property> fcs/filtMeasFL_rpm </property>
        </difference>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/deltaCmdAR_rpm">
        <difference>
          <product>
            <property> fcs/cmdEscAR_nd </property>
            <property> fcs/maxRPM </property>
          </product>
          <property> fcs/filtMeasAR_rpm </property>
        </difference>
      </function>
    </fcs_function>

    <!-- Power Command:
    deltaPower_Watt = torqReq * (deltaCmd_rpm * rpm2rps)
    cmdPower_Watt = deltaPower_Watt + pwrReq_Watt -->
    <fcs_function>
      <function name="fcs/cmdPowerFR_Watt">
        <sum>
          <product>
            <property> propulsion/engine[0]/propeller-sense </property>
            <value> -1 </value> <!-- Torque is negative of prop sense -->
            <property> propulsion/engine[0]/propeller-torque </property>
            <property> fcs/deltaCmdFR_rpm </property>
            <value> 0.104719 </value> <!-- rpm to rad/sec -->
          </product>
          <product>
            <property> propulsion/engine[0]/propeller-power </property>
            <value> 1.3558179 </value> <!-- ft-lbs/s to Watts -->
          </product>
        </sum>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerAL_Watt">
        <sum>
          <product>
            <property> propulsion/engine[1]/propeller-sense </property>
            <value> -1 </value> <!-- Torque is negative of prop sense -->
            <property> propulsion/engine[1]/propeller-torque </property>
            <property> fcs/deltaCmdAL_rpm </property>
            <value> 0.104719 </value> <!-- rpm to rad/sec -->
          </product>
          <product>
            <property> propulsion/engine[1]/propeller-power </property>
            <value> 1.3558179 </value> <!-- ft-lbs/s to Watts -->
          </product>
        </sum>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerFL_Watt">
        <sum>
          <product>
            <property> propulsion/engine[2]/propeller-sense </property>
            <value> -1 </value> <!-- Torque is negative of prop sense -->
            <property> propulsion/engine[2]/propeller-torque </property>
            <property> fcs/deltaCmdFL_rpm </property>
            <value> 0.104719 </value> <!-- rpm to rad/sec -->
          </product>
          <product>
            <property> propulsion/engine[2]/propeller-power </property>
            <value> 1.3558179 </value> <!-- ft-lbs/s to Watts -->
          </product>
        </sum>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerAR_Watt">
        <sum>
          <product>
            <property> propulsion/engine[3]/propeller-sense </property>
            <value> -1 </value> <!-- Torque is negative of prop sense -->
            <property> propulsion/engine[3]/propeller-torque </property>
            <property> fcs/deltaCmdAR_rpm </property>
            <value> 0.104719 </value> <!-- rpm to rad/sec -->
          </product>
          <product>
            <property> propulsion/engine[3]/propeller-power </property>
            <value> 1.3558179 </value> <!-- ft-lbs/s to Watts -->
          </product>
        </sum>
      </function>
    </fcs_function>

    <!-- Convert power command to normalized throttle Command -->
    <fcs_function>
      <function name="fcs/cmdPowerFR_nd">
        <quotient>
          <property> fcs/cmdPowerFR_Watt </property>
          <property> fcs/maxPwr_Watt </property>
        </quotient>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerAL_nd">
        <quotient>
          <property> fcs/cmdPowerAL_Watt </property>
          <property> fcs/maxPwr_Watt </property>
        </quotient>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerFL_nd">
        <quotient>
          <property> fcs/cmdPowerFL_Watt </property>
          <property> fcs/maxPwr_Watt </property>
        </quotient>
      </function>
    </fcs_function>
    <fcs_function>
      <function name="fcs/cmdPowerAR_nd">
        <quotient>
          <property> fcs/cmdPowerAR_Watt </property>
          <property> fcs/maxPwr_Watt </property>
        </quotient>
      </function>
    </fcs_function>

    <actuator name="Front Right">
      <input> fcs/cmdPowerFR_nd </input>
      <clipto>
        <min>0.01</min> <!-- Min command shouldn't be zero, commands would be stuck at zero -->
        <max>1.0</max>
      </clipto>
      <output> fcs/throttle-cmd-norm[0] </output>
    </actuator>

    <actuator name="Aft Left">
      <input> fcs/cmdPowerAL_nd </input>
      <clipto>
        <min>0.01</min>
        <max>1.0</max>
      </clipto>
      <output> fcs/throttle-cmd-norm[1] </output>
    </actuator>

    <actuator name="Front Left">
      <input>fcs/cmdPowerFL_nd</input>
      <clipto>
        <min>0.01</min>
        <max>1.0</max>
      </clipto>
      <output> fcs/throttle-cmd-norm[2] </output>
    </actuator>

    <actuator name="Aft Right">
      <input> fcs/cmdPowerAR_nd </input>
      <clipto>
        <min>0.01</min>
        <max>1.0</max>
      </clipto>
      <output> fcs/throttle-cmd-norm[3] </output>
    </actuator>

  </channel>
</system>

Example motor definition:

<electric_engine name="DJI E305">
  <!-- E305 Motor is a DJI 2312E - 960 -->
  <power unit="WATTS"> 320 </power>
</electric_engine>

Example propeller definition:

<propeller name="DJI 9450" version="1.1">
  <ixx unit="KG*M2"> 6.05e-05 </ixx> <!-- (1/12) * 12.6e-3 * (9.45*0.0254)^2 -->
  <diameter unit="IN"> 9.45 </diameter>
  <numblades> 2 </numblades>
  <constspeed> 0 </constspeed>

  <table name="C_THRUST" type="internal"> <!-- derived from APC website for the 9X4.5e -->
    <tableData>
      0.0000    0.1288
      0.0209    0.1271
      0.0522    0.1252
      0.0730    0.1230
      0.1039    0.1207
      0.1252    0.1181
      0.1470    0.1153
      0.1774    0.1122
      0.1983    0.1089
      0.2287    0.1053
      0.2504    0.1015
      0.2774    0.0975
      0.3022    0.0932
      0.3235    0.0888
      0.3539    0.0842
      0.3757    0.0794
      0.4039    0.0745
      0.4274    0.0695
      0.4496    0.0644
      0.4787    0.0592
      0.5004    0.0538
      0.5296    0.0483
      0.5526    0.0426
      0.5783    0.0369
      0.6039    0.0310
      0.6257    0.0250
      0.6548    0.0189
      0.6774    0.0128
      0.7039    0.0064
      0.7291    -0.0001
    </tableData>
  </table>

  <table name="C_POWER" type = "internal">
    <tableData>
      0.0000  0.0666
      0.0209  0.0647
      0.0522  0.0628
      0.0730  0.0611
      0.1039  0.0595
      0.1252  0.0581
      0.1470  0.0567
      0.1774  0.0554
      0.1983  0.0542
      0.2287  0.0531
      0.2504  0.0520
      0.2774  0.0509
      0.3022  0.0498
      0.3235  0.0485
      0.3539  0.0471
      0.3757  0.0456
      0.4039  0.0440
      0.4274  0.0422
      0.4496  0.0402
      0.4787  0.0381
      0.5004  0.0358
      0.5296  0.0332
      0.5526  0.0305
      0.5783  0.0275
      0.6039  0.0243
      0.6257  0.0210
      0.6548  0.0175
      0.6774  0.0137
      0.7039  0.0099
      0.7291  0.0061
    </tableData>
  </table>

</propeller>

Example propulsion system, uses the engine definition (above) and the propeller definition (above):

<propulsion>
  <engine file="DJI_E305" name="front right">
    <thruster file="DJI_9450">
      <location unit="M">
        <x>-0.1651</x>
        <y>0.1651</y>
        <z>0.025</z>
      </location>
      <orient unit="DEG">
        <roll>0</roll>
        <pitch>90</pitch>
        <yaw>0</yaw>
      </orient>
      <sense>1.0</sense>
      <p_factor>0.0</p_factor>
    </thruster>
  </engine>

  <engine file="DJI_E305" name="aft left">
    <thruster file="DJI_9450">
      <location unit="M">
        <x>0.1651</x>
        <y>-0.1651</y>
        <z>0.025</z>
      </location>
      <orient unit="DEG">
        <roll>0</roll>
        <pitch>90</pitch>
        <yaw>0</yaw>
      </orient>
      <sense>1.0</sense>
      <p_factor>0.0</p_factor>
    </thruster>
  </engine>

  <engine file="DJI_E305" name="front left">
    <thruster file="DJI_9450">
      <location unit="M">
        <x>-0.1651</x>
        <y>-0.1651</y>
        <z>0.025</z>
      </location>
      <orient unit="DEG">
        <roll>0</roll>
        <pitch>90</pitch>
        <yaw>0</yaw>
      </orient>
      <sense>-1.0</sense>
      <p_factor>0.0</p_factor>
    </thruster>
  </engine>

  <engine file="DJI_E305" name="aft right">
    <thruster file="DJI_9450">
      <location unit="M">
        <x>0.1651</x>
        <y>0.1651</y>
        <z>0.025</z>
      </location>
      <orient unit="DEG">
        <roll>0</roll>
        <pitch>90</pitch>
        <yaw>0</yaw>
      </orient>
      <sense>-1.0</sense>
      <p_factor>0.0</p_factor>
    </thruster>
  </engine>
</propulsion>
bcoconni commented 3 years ago

Great ! :+1:

Just a couple of tips:

bcoconni commented 3 years ago

PR #394 exposes additional properties in FGPropeller: propulsion/engine[#]/propeller-power propulsion/engine[#]/propeller-torque propulsion/engine[#]/propeller-sense

It finally made its way to the master branch. Thanks @rega0051 for your patience (and perseverance 😉).

hbeni commented 2 years ago

Hi there, after these changes, is #138 implemented now, too?

bcoconni commented 2 years ago

@hbeni Unfortunately not. I encourage you to discuss this topic on the issue #138 itself.

pbecchi commented 2 years ago

Hi everybody,

I am new to JSBSIM , my long time objective is to create an eVTOL simulation. I am concerned on the lack of multicopter examples and on the issues related to electric powertrains.

Regarding BLDC electric motors , may be I can give my contribution: As far as I know the most simple and widely used model is the" 3 costants equations">

Now what is best way of coding this ? a script snippet or a new C++ code ?

It could be somehow similar to what you have suggested @bcoconni and @rega0051 but the input properties should be the phisical motor costants: Kv, Rm and I0. I think that the filter you propose ,it a way to simulate the actual behaviour of the BLDC motor and should be replaced by the I*Rm term in the RPM equation.

I will appreciate your feedback and some guidance on how to proceed.

bcoconni commented 2 years ago

Hi @pbecchi and thanks for your interest in JSBSim.

I think C++ code is the best option since other engines are coded in JSBSim that way. Basically, you have 2 options:

  1. Improve the existing electric engine by adding some features to it https://github.com/JSBSim-Team/jsbsim/blob/master/src/models/propulsion/FGElectric.cpp
  2. Build a new engine model just as @mvacanti did in his fork of JSBSim: https://github.com/mvacanti/jsbsim/blob/pr-bldc-validation/src/models/propulsion/FGBldc.cpp
pbecchi commented 2 years ago

@bcoconni thanks a lot for your suggestions. I think that the easyest way for me will be to modify the @mvacanti fork changing the code of FGBldc.cpp. I need to alter the code that compute the generated torque . To do that I need to use a couple on new motor properties ( the internal resistance of motor coils, and the no torque current) and I need to use propulsion/engine[#]/propeller-torque that should be availble from FGpropeller. I only have some C++ background and I need, if possible to get some guidance on how to interface the code , compile and build JSBSIM on VisualStudio. I will prepare a snippet of the code in my next message , i will appreciate comments and corrections.

bcoconni commented 2 years ago

I only have some C++ background and I need, if possible to get some guidance on how to interface the code, compile and build JSBSIM on VisualStudio.

Sure. For a start, you can find some guidance in our docs to build JSBSim with Visual Studio.

I will prepare a snippet of the code in my next message , i will appreciate comments and corrections.

We'll be glad to answer your questions.

In order to keep this issue focused on its topic (propellers, quadcopters, etc.), please open a separate discussion regarding Windows/Visual Studio/compilation or any other topics that are unrelated to this ticket.