From 4eb94843a198e177dfff195e7ac0d3ff6af26eee Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Wed, 27 Dec 2023 15:17:44 +0800 Subject: [PATCH] Default CMA in LiftDrag pluginto zero (#2272) * Default CMA in LiftDrag pluginto zero The changes in #2189 have caused a regression for our upstream users. This fix disables moment calculations by defaulting Cma to zero. It should help mitigate some of the regression. There is also an [ongoing discussion](https://github.com/gazebosim/gz-sim/pull/2189#issuecomment-1866589946) as to whether the cos term should be cos^2 or cos. Signed-off-by: Arjo Chakravarty * remove cos change to address one problem at a time Signed-off-by: Arjo Chakravarty --------- Signed-off-by: Arjo Chakravarty --- src/systems/lift_drag/LiftDrag.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index cd58c9f22c..b16766e6a0 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -74,7 +74,7 @@ class gz::sim::systems::LiftDragPrivate /// \brief Coefficient of Moment / alpha slope. /// Moment = C_M * q * S /// where q (dynamic pressure) = 0.5 * rho * v^2 - public: double cma = 0.01; + public: double cma = 0.0; /// \brief angle of attach when airfoil stalls public: double alphaStall = GZ_PI_2;