PX4 / PX4-SITL_gazebo-classic

Set of plugins, models and worlds to use with OSRF Gazebo Simulator in SITL and HITL.
http://dev.px4.io/simulation-gazebo.html
370 stars 786 forks source link

LiftDragPlugin aerodynamic coefficient improvements #684

Open pjdewitte opened 3 years ago

pjdewitte commented 3 years ago

While working with the LiftDragPlugin I found several issues. I'd like to discuss them here before I start drafting a pull request.

1. Missing coefficients: cd_alpha0 and cm_alpha0

The plugin allows to enter alpha0 (a0 in SDF) to set the agle of attack where the lift is zero. In general, at that point the drag and moment coefficient are not zero. It should be possible to specify these.

2. Missing coefficient: cd_delta

The plugin allows specifying how the lift and moment change when a control surface is deflected, but not how the drag changes. For completeness, I propose to add this.

3. Bug: sideslip corrected for twice

The plugin corrects for sideslip by extracting the velocity vector perpendicular to the wing (velInLDPlane) from the 3D velocity (vel), but also by multiplying the aerodynamic coefficients by the cosine of the sweep angle, where sweep here doesn't refer to the wing geometric sweep but to the swept position in the airflow. The cosine correction is not required if the velocity is already corrected for. (In addition, I also believe it should be the square of the cosine, if you would correct it that way.) I propose to remove cosSweepAngle.

4. Stall and large angle-of-attack (AoA) behaviour

Currently the Plugin calculates forces and moments up to 90 degrees AoA, after that all aerodynamic forces and moments are zero. For normal planes this is sufficient, but for tailsitter VTOL, 90 degrees pitch is a standard operating point, and switching between applying forces and not applying forces in that region is not realistic.

At very high angles of attack, a wing behaves more and more like a flat plate. For an infinite flat plate, the coefficients are approximately (http://groups.csail.mit.edu/robotics-center/public_papers/Hoburg09a.pdf):

cl = 2 sin(alpha) cos(alpha); cd = 2 * sin(alpha)^2;

Although for a finite wing the coefficients will be different, using these coefficients will already be an improvement compared to the current situation. Rather than taking the maximum of the calculated lift coefficient and 0, we can take the maximum of the calculated lift coefficient and flat plat lift coefficient.

For cm, I haven't been able to find an expression yet. Currently cm is kept positive for positive AoA and negative for negative AoA after stalling, but I'm not sure this is valid in all cases. Perhaps it might make more sense to remove this constraint and let the user take full control by setting cmaStall appropriately?

5. Consistency

controlJointRadToCL is not consistent with cm_delta and the other parameters. I propose to allow the use of cl_delta in SDF and deprecate (but still support) controlJointRadToCL.

alpha0 is called a0 in the SDF (and alpha0 in the plugin code). I propose to allow the use of alpha0 in SDF and deprecate (but still support) a0.

I can make this a separate pull request if this needs further consideration.

Pull request

I'm planning to draft a pull request next week. If you have feedback or ideas, let's discuss here!

LorenzMeier commented 3 years ago

The current implementation started as an initial proof of concept and has been built out in iterations. So your observations make sense and the improvements you are proposing make a lot of sense. A pull request would be much appreciated. @RomanBapst @markusachtelik FYI

Jaeyoung-Lim commented 3 years ago

@pjdewitte Thanks for looking into the plugin in detail. Most of the issues are understood, but we need to factor this out into two directions. a) improving the existing liftdrag plugin b) Adding a more advanced aerodynamics plugin

pjdewitte commented 3 years ago

Thanks for the feedback. I'll address 1/2/3/5 with a pull request.

@Jaeyoung-Lim Is there information, documentation or are there requirements about how the aerodynamics plugin will work? With aerodynamics things can get complex very easily, so I'm wondering where the line will be drawn.

We (the company I work for) also identified the desire for a plugin, which works on the system level, i.e. calculates the lift, drag, sideslip force, pitch moment, roll moment and yaw moment due to aerodynamics at the system level, rather than at the level of each component like the liftdragplugin does, because test flights result in system-level observations, which can be used to make the simulation match reality. Perhaps that is also one of the goals?

I agree that multiple use cases exist, yet perhaps it is possible to replace the LiftDrag plugin entirely if it is a subset of the new plugin's functionality, which would be good from a maintenance perspective.

pjdewitte commented 3 years ago

Regarding 4: I still think it would be good to add somewhat realistic stall behavior to the LiftDrag plugin, at least until a better plugin becomes available. It might be a while until I find the time to add this though.

Let me know here if a pull request would be appreciated if I actually find the time to do it. In the meantime, I'm OK with closing this issue when #690 is merged in.

Jaeyoung-Lim commented 3 years ago

@pjdewitte Would be definitely appreciated! Though the one requirement would be that it should not slow down the sim.