Skip to content

Commit

Permalink
Use GZ_PI instead of M_PI to fix windows builds (#2230)
Browse files Browse the repository at this point in the history
Fixes #2229

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Nov 6, 2023
1 parent 45233fc commit 82fbdba
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion examples/standalone/marker/marker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
4 changes: 2 additions & 2 deletions src/systems/advanced_lift_drag/AdvancedLiftDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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)));

Expand Down
4 changes: 2 additions & 2 deletions test/integration/added_mass.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 82fbdba

Please sign in to comment.