Skip to content

Commit

Permalink
Remove redundant namespace references (#479)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon authored Aug 10, 2022
1 parent eb9183f commit 29e3f41
Show file tree
Hide file tree
Showing 14 changed files with 163 additions and 163 deletions.
10 changes: 5 additions & 5 deletions src/AxisAlignedBox.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ AxisAlignedBox::AxisAlignedBox(double _vec1X, double _vec1Y, double _vec1Z,
this->dataPtr->min.Set(_vec1X, _vec1Y, _vec1Z);
this->dataPtr->max.Set(_vec2X, _vec2Y, _vec2Z);

this->dataPtr->min.Min(math::Vector3d(_vec2X, _vec2Y, _vec2Z));
this->dataPtr->max.Max(math::Vector3d(_vec1X, _vec1Y, _vec1Z));
this->dataPtr->min.Min(Vector3d(_vec2X, _vec2Y, _vec2Z));
this->dataPtr->max.Max(Vector3d(_vec1X, _vec1Y, _vec1Z));
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -93,15 +93,15 @@ double AxisAlignedBox::ZLength() const
}

//////////////////////////////////////////////////
math::Vector3d AxisAlignedBox::Size() const
Vector3d AxisAlignedBox::Size() const
{
return math::Vector3d(this->XLength(),
return Vector3d(this->XLength(),
this->YLength(),
this->ZLength());
}

//////////////////////////////////////////////////
math::Vector3d AxisAlignedBox::Center() const
Vector3d AxisAlignedBox::Center() const
{
return 0.5 * this->dataPtr->min + 0.5 * this->dataPtr->max;
}
Expand Down
2 changes: 1 addition & 1 deletion src/AxisAlignedBox_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -598,6 +598,6 @@ TEST(AxisAlignedBoxTest, Volume)
AxisAlignedBox box;
EXPECT_DOUBLE_EQ(0.0, box.Volume());

AxisAlignedBox box2(math::Vector3d(-1, -2, -3), math::Vector3d(1, 2, 3));
AxisAlignedBox box2(Vector3d(-1, -2, -3), Vector3d(1, 2, 3));
EXPECT_DOUBLE_EQ(48.0, box2.Volume());
}
4 changes: 2 additions & 2 deletions src/Frustum_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -283,11 +283,11 @@ TEST(FrustumTest, FOV)
// Pose
Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0));

EXPECT_EQ(frustum.FOV(), math::Angle(IGN_DTOR(45)));
EXPECT_EQ(frustum.FOV(), Angle(IGN_DTOR(45)));

frustum.SetFOV(1.5707);

EXPECT_EQ(frustum.FOV(), math::Angle(1.5707));
EXPECT_EQ(frustum.FOV(), Angle(1.5707));
}

/////////////////////////////////////////////////
Expand Down
10 changes: 5 additions & 5 deletions src/Inertial_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -500,10 +500,10 @@ TEST(Inertiald_Test, Addition)
math::MassMatrix3d cubeMM3;
EXPECT_TRUE(cubeMM3.SetFromBox(mass, size));
EXPECT_EQ(
ignition::math::Vector3d::One,
math::Vector3d::One,
cubeMM3.DiagonalMoments());
EXPECT_EQ(
ignition::math::Vector3d::Zero,
math::Vector3d::Zero,
cubeMM3.OffDiagonalMoments());

const math::Inertiald diagonalCubes =
Expand Down Expand Up @@ -531,13 +531,13 @@ TEST(Inertiald_Test, Addition)
// [ -1.5 -1.5 4.0 ]
//
// then double it to account for both cubes
EXPECT_EQ(ignition::math::Pose3d::Zero, diagonalCubes.Pose());
EXPECT_EQ(math::Pose3d::Zero, diagonalCubes.Pose());
EXPECT_DOUBLE_EQ(mass * 2.0, diagonalCubes.MassMatrix().Mass());
EXPECT_EQ(
ignition::math::Vector3d(8, 8, 8),
math::Vector3d(8, 8, 8),
diagonalCubes.MassMatrix().DiagonalMoments());
EXPECT_EQ(
ignition::math::Vector3d(-3, -3, -3),
math::Vector3d(-3, -3, -3),
diagonalCubes.MassMatrix().OffDiagonalMoments());
}
}
Expand Down
8 changes: 4 additions & 4 deletions src/MovingWindowFilter_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ TEST(MovingWindowFilterTest, FilterSomething)
{
math::MovingWindowFilter<double> doubleMWF;
math::MovingWindowFilter<double> doubleMWF2;
math::MovingWindowFilter<ignition::math::Vector3d> vectorMWF;
math::MovingWindowFilter<math::Vector3d> vectorMWF;

doubleMWF.SetWindowSize(10);
doubleMWF2.SetWindowSize(2);
Expand All @@ -49,7 +49,7 @@ TEST(MovingWindowFilterTest, FilterSomething)
{
doubleMWF.Update(static_cast<double>(i));
doubleMWF2.Update(static_cast<double>(i));
ignition::math::Vector3d v(1.0*static_cast<double>(i),
math::Vector3d v(1.0*static_cast<double>(i),
2.0*static_cast<double>(i),
3.0*static_cast<double>(i));
vectorMWF.Update(v);
Expand All @@ -61,9 +61,9 @@ TEST(MovingWindowFilterTest, FilterSomething)
EXPECT_DOUBLE_EQ(doubleMWF.Value(), sum/10.0);
EXPECT_DOUBLE_EQ(doubleMWF2.Value(), (18.0+19.0)/2.0);

ignition::math::Vector3d vsum;
math::Vector3d vsum;
for (unsigned int i = 0; i < 20; ++i)
vsum += ignition::math::Vector3d(1.0*static_cast<double>(i),
vsum += math::Vector3d(1.0*static_cast<double>(i),
2.0*static_cast<double>(i),
3.0*static_cast<double>(i));
EXPECT_EQ(vectorMWF.Value(), vsum / 20.0);
Expand Down
12 changes: 6 additions & 6 deletions src/OrientedBox_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ TEST(OrientedBoxTest, EmptyConstructorNew)

EXPECT_TRUE(box->Size() == Vector3d::Zero);
EXPECT_TRUE(box->Pose() == Pose3d::Zero);
EXPECT_EQ(math::Material(), box->Material());
EXPECT_EQ(Material(), box->Material());

{
delete box;
Expand Down Expand Up @@ -340,15 +340,15 @@ TEST(OrientedBoxTest, OperatorStreamOut)
TEST(OrientedBoxTest, VolumeAndDensity)
{
double mass = 1.0;
math::OrientedBoxd box(Vector3d(1.0, 0.1, 10.4));
OrientedBoxd box(Vector3d(1.0, 0.1, 10.4));
double expectedVolume = 1.0 * 0.1 * 10.4;
EXPECT_DOUBLE_EQ(expectedVolume, box.Volume());

double expectedDensity = mass / expectedVolume;
EXPECT_DOUBLE_EQ(expectedDensity, box.DensityFromMass(mass));

// Bad density
math::OrientedBoxd box2;
OrientedBoxd box2;
EXPECT_GT(0.0, box2.DensityFromMass(mass));
}

Expand All @@ -359,15 +359,15 @@ TEST(OrientedBoxTest, Mass)
double l = 2.0;
double w = 0.1;
double h = 34.12;
math::OrientedBoxd box(Vector3d(l, w, h));
OrientedBoxd box(Vector3d(l, w, h));
box.SetDensityFromMass(mass);

math::MassMatrix3d massMat;
MassMatrix3d massMat;
double ixx = (1.0/12.0) * mass * (w*w + h*h);
double iyy = (1.0/12.0) * mass * (l*l + h*h);
double izz = (1.0/12.0) * mass * (l*l + w*w);

math::MassMatrix3d expectedMassMat;
MassMatrix3d expectedMassMat;
expectedMassMat.SetInertiaMatrix(ixx, iyy, izz, 0.0, 0.0, 0.0);
expectedMassMat.SetMass(mass);

Expand Down
2 changes: 1 addition & 1 deletion src/PID.cc
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ double PID::Update(const double _error,
const std::chrono::duration<double> &_dt)
{
if (_dt == std::chrono::duration<double>(0) ||
ignition::math::isnan(_error) || std::isinf(_error))
isnan(_error) || std::isinf(_error))
{
return 0.0;
}
Expand Down
4 changes: 2 additions & 2 deletions src/RotationSpline.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,9 @@ Quaterniond RotationSpline::Interpolate(const unsigned int _fromIndex,
}

// Fast special cases
if (math::equal(_t, 0.0))
if (equal(_t, 0.0))
return this->dataPtr->points[_fromIndex];
else if (math::equal(_t, 1.0))
else if (equal(_t, 1.0))
return this->dataPtr->points[_fromIndex + 1];

// double interpolation
Expand Down
6 changes: 3 additions & 3 deletions src/SpeedLimiter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ double SpeedLimiter::LimitVelocity(double &_vel) const
{
const double vUnclamped = _vel;

_vel = ignition::math::clamp(
_vel = clamp(
_vel, this->dataPtr->minVelocity, this->dataPtr->maxVelocity);

return _vel - vUnclamped;
Expand All @@ -161,7 +161,7 @@ double SpeedLimiter::LimitAcceleration(double &_vel, double _prevVel,

const double accUnclamped = (_vel - _prevVel) / dtSec;

const double accClamped = ignition::math::clamp(accUnclamped,
const double accClamped = clamp(accUnclamped,
this->dataPtr->minAcceleration, this->dataPtr->maxAcceleration);

_vel = _prevVel + accClamped * dtSec;
Expand All @@ -184,7 +184,7 @@ double SpeedLimiter::LimitJerk(double &_vel, double _prevVel,
const double accPrev = (_prevVel - _prevPrevVel) / dtSec;
const double jerkUnclamped = (accUnclamped - accPrev) / dtSec;

const double jerkClamped = ignition::math::clamp(jerkUnclamped,
const double jerkClamped = clamp(jerkUnclamped,
this->dataPtr->minJerk, this->dataPtr->maxJerk);

const double accClamped = accPrev + jerkClamped * dtSec;
Expand Down
Loading

0 comments on commit 29e3f41

Please sign in to comment.