-
Notifications
You must be signed in to change notification settings - Fork 466
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Propeller, engine improvements to support quadcopters etc. #333
Comments
There are quite a number of interesting topics that you are bringing up here 😄 Direction of the propeller axisRegarding the propeller axis that is limited to the X-axis, you have to keep in mind that
jsbsim/src/models/propulsion/FGThruster.cpp Lines 95 to 102 in 9660986
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):jsbsim/src/models/propulsion/FGPropeller.cpp Lines 206 to 208 in 9660986
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).Lines 413 to 426 in 9660986
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 orientationjsbsim/aircraft/J246/Systems/J246FirstStageEffectors.xml Lines 32 to 44 in 9660986
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 limitIt 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 motorsIndeed, 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 engineA 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. |
Will do, just getting more familiar with the code first.
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 - #253 (comment) 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. |
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.
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 |
@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):
The results of completing the flight plan above (climb to altitude then yaw to a heading) produces a .csv file that
Given BOUABDALLAH, MURRIERI, and SIEGWART (p. 175 (5)) we would expect that the Total N moment calculated by JSBSim Plotting the .csv file generate by JSBSim for this flight we observe that the Total N moment is equal to the sum of the |
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
|
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:
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. Looking at the power usage in this condition: 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. |
I may be wrong but CP and CQ are really 2 sides of the same coin which means that the relationship Furthermore, the relationship you suggest for the efficiency does not stand because you did not check your units 😄
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.
As I mentioned above I think this table would be redundant with |
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 propellerOn figure 8.2-1 Stevens & Lewis show how the various torques add or subtract to influence the propeller and aircraft motions. First, the propeller power is computed from the jsbsim/src/models/propulsion/FGPropeller.cpp Line 294 in 05bd64a
then the torque is obtained by dividing the power by the propeller angular rate jsbsim/src/models/propulsion/FGPropeller.cpp Lines 351 to 352 in 05bd64a
and finally the torque is added to the aircraft moments (after being transformed from the propeller frame to the body frame) jsbsim/src/models/propulsion/FGPropeller.cpp Lines 280 to 282 in 05bd64a
So what is implemented in JSBSim is the red arrow below: According to that, I think that the torque --- 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 frameAnother 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):
However, in JSBSim, the air velocity is obtained from Lines 513 to 514 in 05bd64a
then transferred to the thruster by FGEngine (the member FGEngine::in is a simple reference to FGPropulsion::in )jsbsim/src/models/propulsion/FGEngine.cpp Lines 149 to 155 in 05bd64a
and finally used by FGPropeller after a simple transformation from the body frame to the propeller frame:jsbsim/src/models/propulsion/FGPropeller.cpp Lines 201 to 206 in 05bd64a
It is therefore obvious that the term 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 --- 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 Let me know what you all think. |
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 ?
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: The work on the air flow upstream of the propeller during a time interval dt is: The work on the air flow downstream of the propeller during a time interval dt is: So the power produced by the propeller is or For a hovering propeller we have |
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. |
…s local velocities. As per the discussion in the issue #333 and eqn 8.2-1 in Stevens & Lewis' "Aircraft Control & Simulation".
@pbecchi for an existing multicopter model you should look at the DJI F450 that I was using earlier. Note that in F450.xml you can change: to in order to remove the loop closure I made around the ESC and motors to get a desired frequency cutoff. It's good to see that you're using internal resistance and no load current. I had elected to go with just a cut-off frequency because I believe the motor model is otherwise a too stiff ODE and the actual response of a real physical system doesn't have response out nearly high enough to cause issues running JSBSim with a typical dt. Any kind of damping and high-frequency cutoff would help that situation, hopefully the physical motor parameters will be sufficient to mitigate the stiffness without warranting the outer-loop closure method that I ended up using. Both internal resistance and no load current are pretty easy to measure even if the spec sheets don't always list them. |
@rega0051 |
Great ! Thanks.
The motor output power |
@pbecchi, unless I'm mistaken you have not brought an answer to my question: why is the motor power output oscillating in the previous chart you've shown ? Given the simple model you told you're using, this is quite unexpected. In addition, I don't see any fork of JSBSim under your GitHub user name so it's quite difficult to provide you with further comments if we can't review your code. |
@bcoconni , you are right! Sorry I was busy with the F450 tests.... TorqueAvailable = MaxTorque - TorqueRequired;
DeltaTorque = (((DeltaRPM/60)*(2.0 * M_PI))/(max(0.00001, in.TotalDeltaT))) * ((FGPropeller*)Thruster)->GetIxx();
TorqueAvailable = MaxTorque - TorqueRequired;
if (DeltaRPM >= 0) {
TargetTorque = min(DeltaTorque, TorqueAvailable) + TorqueRequired;
} else {
TargetTorque = min(abs(DeltaTorque), TorqueRequired) * -1;
}
EnginePower = ((2 * M_PI) * max(RPM, 0.0001) * TargetTorque) / 60; Since i am a beginner and i have not any knowledge of JSBSim, I have decided to use the existing code of FGBLdc.cpp written by @mvacanti with minimal modifications. I have worked using his fork and i have run his test scripts. |
@bcoconni @bcoconni @rega0051 I will appreciate your comments! |
Thanks for the updates @pbecchi. This looks very good. I was a bit surprised that the motor accelerates much faster than it decelerates so I had a look to your code and found the following statement: if (DeltaRPM >= 0) {
TargetTorque = min(DeltaTorque, TorqueAvailable) + TorqueRequired;
}
else {
TargetTorque = TorqueRequired - abs(DeltaTorque)*abs(DeltaRPM)/max(RPM,0.001);
TargetTorque = TorqueRequired*(CommandedRPM / max(RPM,0.01))* (CommandedRPM / max(RPM, 0.01));
} The different treatment based on the sign of
|
Thaks for your comment @bcoconni , in general acceleration and deceleration of a BLDC motor are not comparabele. where you can set the desired deceleration time as you normally do programming the ESC (??? word is "time"). |
@rega0051 , @bcoconni @Jaeyoung-Lim |
@pbecchi Would you be interested in making a PR to https://github.com/Auterion/px4-jsbsim-bridge ? Regarding logging, we can try to add those in the jsbsim bridge |
@Jaeyoung-Lim |
Output can also be specified in the aircraft file as well, e.g. jsbsim/aircraft/c172x/c172x.xml Lines 1207 to 1226 in d9df845
|
@pbecchi, your branch seems to be quite stable, so it could be time to pull your changes. We'd be glad to review your PR 😃. |
There are a few topics that remain open for discussion however: Why is
|
DeltaRPM = round((V - CurrentRequired * CoilResistance) * VelocityConstant); |
I'd expect that to be a destabilizing factor, numerically speaking since the engine power will increase (resp. decrease) discretely rather than increasing (resp. decreasing) continuously.
Why is EnginePower
prevented from going to zero ?
EnginePower = ((2 * M_PI) * max(RPM, 0.0001) * TargetTorque) / 60; //units [#*ft/s] |
There is this
max(RPM, 0.0001)
factor. What's wrong with having EnginePower
== 0.0 ?
Joule heating is limited to the motor deceleration ?
There is this strange expression RPM*TorqueConstant/VelocityConstant/VelocityConstant/CoilResistance
:
jsbsim/src/models/propulsion/FGBrushLessDCMotor.cpp
Lines 165 to 170 in d3536e9
if (DeltaRPM >= 0) { | |
TargetTorque = min(InertiaTorque, TorqueAvailable) + TorqueRequired; | |
} else { | |
// Deceleration is due to braking force given by the ESC and set by parameter deceleration_time | |
TargetTorque = TorqueRequired - min(abs(InertiaTorque)/(max(DecelerationFactor,0.01)*30),RPM*TorqueConstant/VelocityConstant/VelocityConstant/CoilResistance); | |
} |
and I have this gut feeling that it is linked to the Joule heating. What else could dissipate energy during deceleration in an electric motor ?
However, would RPM*TorqueConstant/VelocityConstant/VelocityConstant/CoilResistance
be characterizing the Joule heating then it should apply to the acceleration as well but it doesn't. So what is this factor ?
And I'm looking forward to your next PR @pbecchi that will include example usage of the new brushless DC motor in order to carry out some experiments with your code 😉
Thanks for merging the PR. I am a little concerned on the number of corrections this PR will originate: this my first JSBSIM FDM and I have to derive it from an existing model without full understanding of all inputs. From another perspective ......I have a good opportunity to learn :-) |
Let discuss a little more on example PR: |
@pbecchi yep, I created this initial discussion in Oct 2020 to discuss propeller and engine improvements for quadcopters etc. and it's a pretty long discussion by now. So rather create a new discussion for the sample quadcopter FDM. I'd suggest we continue discussing any outstanding questions/issues with your BLDC implementation here though. |
@bcoconni |
Submit a PR with a commit just for the changes to |
Any progress in this direction? |
Yes .....it is working |
@pbecchi was the VTOL work fruitful? |
Hi
Yes, actually the model of the eVTOL work well and well as simulations with PX4 SITL .
Some improvements may be necessary to model battery and his energy loss
Paolo Becchi
From: Edson Filho ***@***.***>
Sent: 17 October 2024 14:45
To: JSBSim-Team/jsbsim ***@***.***>
Cc: pbecchi ***@***.***>; Mention ***@***.***>
Subject: Re: [JSBSim-Team/jsbsim] Propeller, engine improvements to support quadcopters etc. (#333)
@pbecchi <https://github.com/pbecchi> was the VTOL work fruitful?
—
Reply to this email directly, view it on GitHub <#333 (comment)> , or unsubscribe <https://github.com/notifications/unsubscribe-auth/ACBCZMXAFXZJ3S7ONIMVIHTZ36WMPAVCNFSM6AAAAABQDVIATGVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMZDIMJZGQ2DOMZRHE> .
You are receiving this because you were mentioned.Message ID: ***@***.***>
|
Thanks so much for the answer @pbecchi. Is this eVTOL model public? In JSBsim official repo I can only find the F450 but not a working VTOL |
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:
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.
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:jsbsim/src/models/propulsion/FGPropeller.cpp
Line 78 in 4fe1aa7
I also noticed the following:
jsbsim/src/models/propulsion/FGPropeller.cpp
Lines 53 to 56 in 4fe1aa7
So the x-axis assumption is going to be an issue:
jsbsim/src/models/propulsion/FGPropeller.cpp
Line 270 in 4fe1aa7
jsbsim/src/models/propulsion/FGPropeller.cpp
Line 357 in 4fe1aa7
jsbsim/src/models/propulsion/FGPropeller.cpp
Line 211 in 4fe1aa7
The text was updated successfully, but these errors were encountered: