From 5e669886530b572c4442d91e35463d16a80b18f8 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Mon, 6 Nov 2023 14:54:24 -0600 Subject: [PATCH] Use `GZ_PI` instead of `M_PI` to fix windows builds Fixes #2229 Signed-off-by: Addisu Z. Taddese --- examples/standalone/marker/marker.cc | 2 +- src/systems/advanced_lift_drag/AdvancedLiftDrag.cc | 4 ++-- test/integration/added_mass.cc | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/standalone/marker/marker.cc b/examples/standalone/marker/marker.cc index 5cf7e725ba..68334cffc3 100644 --- a/examples/standalone/marker/marker.cc +++ b/examples/standalone/marker/marker.cc @@ -172,7 +172,7 @@ int main(int _argc, char **_argv) gz::msgs::Set(markerMsg.add_point(), gz::math::Vector3d(0, 0, 0.05)); double radius = 2; - for (double t = 0; t <= M_PI; t+= 0.01) + for (double t = 0; t <= GZ_PI; t+= 0.01) { gz::msgs::Set(markerMsg.add_point(), gz::math::Vector3d(radius * cos(t), radius * sin(t), 0.05)); diff --git a/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc b/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc index 42d6efc189..a4da3147e4 100644 --- a/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc +++ b/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc @@ -615,7 +615,7 @@ void AdvancedLiftDragPrivate::Update(EntityComponentManager &_ecm) { components::JointPosition *tmp_controlJointPosition = controlJointPosition_vec[i]; - controlAngle = tmp_controlJointPosition->Data()[0] * 180/M_PI; + controlAngle = tmp_controlJointPosition->Data()[0] * 180 / GZ_PI; } // AVL's and Gazebo's direction of "positive" deflection may be different. @@ -671,7 +671,7 @@ void AdvancedLiftDragPrivate::Update(EntityComponentManager &_ecm) double CD_fp = 2 / (1 + exp(this->CD_fp_k1 + this->CD_fp_k2 * ( std::max(this->AR, 1 / this->AR)))); - CD = (1 - sigma) * (this->CD0 + (CL*CL) / (M_PI * this->AR * + CD = (1 - sigma) * (this->CD0 + (CL*CL) / (GZ_PI * this->AR * this->eff)) + sigma * abs( CD_fp * (0.5 - 0.5 * cos(2 * this->alpha))); diff --git a/test/integration/added_mass.cc b/test/integration/added_mass.cc index a751b10bba..231cb8f516 100644 --- a/test/integration/added_mass.cc +++ b/test/integration/added_mass.cc @@ -50,13 +50,13 @@ const double kRate = 1000; const double kForceVec[3] = {2000, 2000, 0}; // Force excitation angular velocity [rad / s]. -const double kForceAngVel = 3 * M_PI; +const double kForceAngVel = 3 * GZ_PI; // Torque excitation amplitude and direction. const double kTorqueVec[3] = {200, 200, 0}; // Torque excitation angular velocity [rad / s]. -const double kTorqueAngVel = 2 * M_PI; +const double kTorqueAngVel = 2 * GZ_PI; // Total duration of the motion in iterations. const uint64_t kIter = 1000;