Skip to content

Commit 82fbdba

Browse files
authored
Use GZ_PI instead of M_PI to fix windows builds (#2230)
Fixes #2229 Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org>
1 parent 45233fc commit 82fbdba

File tree

3 files changed

+5
-5
lines changed

3 files changed

+5
-5
lines changed

examples/standalone/marker/marker.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ int main(int _argc, char **_argv)
172172
gz::msgs::Set(markerMsg.add_point(),
173173
gz::math::Vector3d(0, 0, 0.05));
174174
double radius = 2;
175-
for (double t = 0; t <= M_PI; t+= 0.01)
175+
for (double t = 0; t <= GZ_PI; t+= 0.01)
176176
{
177177
gz::msgs::Set(markerMsg.add_point(),
178178
gz::math::Vector3d(radius * cos(t), radius * sin(t), 0.05));

src/systems/advanced_lift_drag/AdvancedLiftDrag.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -615,7 +615,7 @@ void AdvancedLiftDragPrivate::Update(EntityComponentManager &_ecm)
615615
{
616616
components::JointPosition *tmp_controlJointPosition =
617617
controlJointPosition_vec[i];
618-
controlAngle = tmp_controlJointPosition->Data()[0] * 180/M_PI;
618+
controlAngle = tmp_controlJointPosition->Data()[0] * 180 / GZ_PI;
619619
}
620620

621621
// AVL's and Gazebo's direction of "positive" deflection may be different.
@@ -671,7 +671,7 @@ void AdvancedLiftDragPrivate::Update(EntityComponentManager &_ecm)
671671

672672
double CD_fp = 2 / (1 + exp(this->CD_fp_k1 + this->CD_fp_k2 * (
673673
std::max(this->AR, 1 / this->AR))));
674-
CD = (1 - sigma) * (this->CD0 + (CL*CL) / (M_PI * this->AR *
674+
CD = (1 - sigma) * (this->CD0 + (CL*CL) / (GZ_PI * this->AR *
675675
this->eff)) + sigma * abs(
676676
CD_fp * (0.5 - 0.5 * cos(2 * this->alpha)));
677677

test/integration/added_mass.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -50,13 +50,13 @@ const double kRate = 1000;
5050
const double kForceVec[3] = {2000, 2000, 0};
5151

5252
// Force excitation angular velocity [rad / s].
53-
const double kForceAngVel = 3 * M_PI;
53+
const double kForceAngVel = 3 * GZ_PI;
5454

5555
// Torque excitation amplitude and direction.
5656
const double kTorqueVec[3] = {200, 200, 0};
5757

5858
// Torque excitation angular velocity [rad / s].
59-
const double kTorqueAngVel = 2 * M_PI;
59+
const double kTorqueAngVel = 2 * GZ_PI;
6060

6161
// Total duration of the motion in iterations.
6262
const uint64_t kIter = 1000;

0 commit comments

Comments
 (0)