Skip to content

Commit

Permalink
Make API / naming consistent for Frustum, Edge, Angle (#329)
Browse files Browse the repository at this point in the history
Signed-off-by: Akshat Pandya <[email protected]>
  • Loading branch information
akshatpandya authored Dec 28, 2021
1 parent 04a4c85 commit cf10674
Show file tree
Hide file tree
Showing 6 changed files with 50 additions and 47 deletions.
3 changes: 2 additions & 1 deletion include/ignition/math/DiffDriveOdometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,8 @@ namespace ignition
/// \param[in] _leftWheelRadius Radius of the left wheel.
/// \param[in] _rightWheelRadius Radius of the right wheel.
public: void SetWheelParams(double _wheelSeparation,
double _leftWheelRadius, double _rightWheelRadius);
double _leftWheelRadius,
double _rightWheelRadius);

/// \brief Set the velocity rolling window size.
/// \param[in] _size The Velocity rolling window size.
Expand Down
12 changes: 6 additions & 6 deletions include/ignition/math/Frustum.hh
Original file line number Diff line number Diff line change
Expand Up @@ -80,10 +80,10 @@ namespace ignition
/// by height of the near or far planes.
/// \param[in] _pose Pose of the frustum, which is the vertex (top of
/// the pyramid).
public: Frustum(const double _near,
const double _far,
public: Frustum(double _near,
double _far,
const math::Angle &_fov,
const double _aspectRatio,
double _aspectRatio,
const math::Pose3d &_pose = math::Pose3d::Zero);

/// \brief Copy Constructor
Expand All @@ -103,7 +103,7 @@ namespace ignition
/// frustum's vertex to the closest plane.
/// \param[in] _near Near distance.
/// \sa Near
public: void SetNear(const double _near);
public: void SetNear(double _near);

/// \brief Get the far distance. This is the distance from the
/// frustum's vertex to the farthest plane.
Expand All @@ -115,7 +115,7 @@ namespace ignition
/// frustum's vertex to the farthest plane.
/// \param[in] _far Far distance.
/// \sa Far
public: void SetFar(const double _far);
public: void SetFar(double _far);

/// \brief Get the horizontal field of view. The field of view is the
/// angle between the frustum's vertex and the edges of the near or far
Expand All @@ -141,7 +141,7 @@ namespace ignition
/// of the near or far planes.
/// \param[in] _aspectRatio The frustum's aspect ratio.
/// \sa AspectRatio
public: void SetAspectRatio(const double _aspectRatio);
public: void SetAspectRatio(double _aspectRatio);

/// \brief Get a plane of the frustum.
/// \param[in] _plane The plane to return.
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/math/graph/Edge.hh
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ namespace graph

/// \brief Set the cost of the edge.
/// \param[in] _newWeight The new cost.
public: void SetWeight(const double _newWeight)
public: void SetWeight(double _newWeight)
{
this->weight = _newWeight;
}
Expand Down Expand Up @@ -214,7 +214,7 @@ namespace graph
/// \param[in] _id Optional unique id.
public: explicit UndirectedEdge(const VertexId_P &_vertices,
const E &_data,
const double _weight,
double _weight,
const EdgeId &_id = kNullId)
: Edge<E>(_vertices, _data, _weight, _id)
{
Expand Down Expand Up @@ -277,7 +277,7 @@ namespace graph
/// \param[in] _id Optional unique id.
public: explicit DirectedEdge(const VertexId_P &_vertices,
const E &_data,
const double _weight,
double _weight,
const EdgeId &_id = kNullId)
: Edge<E>(_vertices, _data, _weight, _id)
{
Expand Down
58 changes: 29 additions & 29 deletions src/Angle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ const Angle Angle::HalfPi = Angle(IGN_PI_2);
const Angle Angle::TwoPi = Angle(IGN_PI * 2.0);

//////////////////////////////////////////////////
Angle::Angle(const double _radian)
Angle::Angle(double _radian)
{
this->value = _radian;
}
Expand Down Expand Up @@ -79,91 +79,91 @@ Angle Angle::Normalized() const
}

//////////////////////////////////////////////////
Angle Angle::operator-(const Angle &angle) const
Angle Angle::operator-(const Angle &_angle) const
{
return Angle(this->value - angle.value);
return Angle(this->value - _angle.value);
}

//////////////////////////////////////////////////
Angle Angle::operator+(const Angle &angle) const
Angle Angle::operator+(const Angle &_angle) const
{
return Angle(this->value + angle.value);
return Angle(this->value + _angle.value);
}

//////////////////////////////////////////////////
Angle Angle::operator*(const Angle &angle) const
Angle Angle::operator*(const Angle &_angle) const
{
return Angle(this->value * angle.value);
return Angle(this->value * _angle.value);
}

//////////////////////////////////////////////////
Angle Angle::operator/(const Angle &angle) const
Angle Angle::operator/(const Angle &_angle) const
{
return Angle(this->value / angle.value);
return Angle(this->value / _angle.value);
}

//////////////////////////////////////////////////
Angle Angle::operator-=(const Angle &angle)
Angle Angle::operator-=(const Angle &_angle)
{
this->value -= angle.value;
this->value -= _angle.value;
return *this;
}

//////////////////////////////////////////////////
Angle Angle::operator+=(const Angle &angle)
Angle Angle::operator+=(const Angle &_angle)
{
this->value += angle.value;
this->value += _angle.value;
return *this;
}

//////////////////////////////////////////////////
Angle Angle::operator*=(const Angle &angle)
Angle Angle::operator*=(const Angle &_angle)
{
this->value *= angle.value;
this->value *= _angle.value;
return *this;
}

//////////////////////////////////////////////////
Angle Angle::operator/=(const Angle &angle)
Angle Angle::operator/=(const Angle &_angle)
{
this->value /= angle.value;
this->value /= _angle.value;
return *this;
}

//////////////////////////////////////////////////
bool Angle::operator==(const Angle &angle) const
bool Angle::operator==(const Angle &_angle) const
{
return equal(this->value, angle.value, 0.001);
return equal(this->value, _angle.value, 0.001);
}

//////////////////////////////////////////////////
bool Angle::operator!=(const Angle &angle) const
bool Angle::operator!=(const Angle &_angle) const
{
return !(*this == angle);
return !(*this == _angle);
}

//////////////////////////////////////////////////
bool Angle::operator<(const Angle &angle) const
bool Angle::operator<(const Angle &_angle) const
{
return this->value < angle.value;
return this->value < _angle.value;
}

//////////////////////////////////////////////////
bool Angle::operator<=(const Angle &angle) const
bool Angle::operator<=(const Angle &_angle) const
{
return this->value < angle.value || equal(this->value, angle.value);
return this->value < _angle.value || equal(this->value, _angle.value);
}

//////////////////////////////////////////////////
bool Angle::operator>(const Angle &angle) const
bool Angle::operator>(const Angle &_angle) const
{
return this->value > angle.value;
return this->value > _angle.value;
}

//////////////////////////////////////////////////
bool Angle::operator>=(const Angle &angle) const
bool Angle::operator>=(const Angle &_angle) const
{
return this->value > angle.value || equal(this->value, angle.value);
return this->value > _angle.value || equal(this->value, _angle.value);
}

//////////////////////////////////////////////////
Expand Down
6 changes: 4 additions & 2 deletions src/DiffDriveOdometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@ class ignition::math::DiffDriveOdometryPrivate
/// Runge-Kutta.
/// \param[in] _linear Linear velocity.
/// \param[in] _angular Angular velocity.
public: void IntegrateRungeKutta2(double _linear, double _angular);
public: void IntegrateRungeKutta2(double _linear,
double _angular);

/// \brief Integrates the velocities (linear and angular) using exact
/// method.
Expand Down Expand Up @@ -223,7 +224,8 @@ void DiffDriveOdometryPrivate::IntegrateRungeKutta2(
}

//////////////////////////////////////////////////
void DiffDriveOdometryPrivate::IntegrateExact(double _linear, double _angular)
void DiffDriveOdometryPrivate::IntegrateExact(double _linear,
double _angular)
{
if (std::fabs(_angular) < 1e-6)
{
Expand Down
12 changes: 6 additions & 6 deletions src/Frustum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@ Frustum::Frustum()
}

/////////////////////////////////////////////////
Frustum::Frustum(const double _near,
const double _far,
Frustum::Frustum(double _near,
double _far,
const Angle &_fov,
const double _aspectRatio,
double _aspectRatio,
const Pose3d &_pose)
: dataPtr(new FrustumPrivate(_near, _far, _fov, _aspectRatio, _pose))
{
Expand Down Expand Up @@ -171,7 +171,7 @@ double Frustum::Near() const
}

/////////////////////////////////////////////////
void Frustum::SetNear(const double _near)
void Frustum::SetNear(double _near)
{
this->dataPtr->near = _near;
this->ComputePlanes();
Expand All @@ -184,7 +184,7 @@ double Frustum::Far() const
}

/////////////////////////////////////////////////
void Frustum::SetFar(const double _far)
void Frustum::SetFar(double _far)
{
this->dataPtr->far = _far;
this->ComputePlanes();
Expand Down Expand Up @@ -223,7 +223,7 @@ double Frustum::AspectRatio() const
}

/////////////////////////////////////////////////
void Frustum::SetAspectRatio(const double _aspectRatio)
void Frustum::SetAspectRatio(double _aspectRatio)
{
this->dataPtr->aspectRatio = _aspectRatio;
this->ComputePlanes();
Expand Down

0 comments on commit cf10674

Please sign in to comment.