Skip to content

Commit

Permalink
[wpimath] Replace pi with symbol in docs (#7322)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Nov 2, 2024
1 parent 2cfe114 commit dfd1084
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 11 deletions.
2 changes: 1 addition & 1 deletion wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ public static double inputModulus(double input, double minimumInput, double maxi
}

/**
* Wraps an angle to the range -pi to pi radians.
* Wraps an angle to the range -π to π radians.
*
* @param angleRadians Angle to wrap in radians.
* @return The wrapped angle.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ public LinearFilter(double[] ffGains, double[] fbGains) {
* Creates a one-pole IIR low-pass filter of the form: y[n] = (1-gain) x[n] + gain y[n-1] where
* gain = e<sup>-dt / T</sup>, T is the time constant in seconds.
*
* <p>Note: T = 1 / (2 pi f) where f is the cutoff frequency in Hz, the frequency above which the
* <p>Note: T = 1 / (2πf) where f is the cutoff frequency in Hz, the frequency above which the
* input starts to attenuate.
*
* <p>This filter is stable for time constants greater than zero.
Expand All @@ -101,7 +101,7 @@ public static LinearFilter singlePoleIIR(double timeConstant, double period) {
* Creates a first-order high-pass filter of the form: y[n] = gain x[n] + (-gain) x[n-1] + gain
* y[n-1] where gain = e<sup>-dt / T</sup>, T is the time constant in seconds.
*
* <p>Note: T = 1 / (2 pi f) where f is the cutoff frequency in Hz, the frequency below which the
* <p>Note: T = 1 / (2πf) where f is the cutoff frequency in Hz, the frequency below which the
* input starts to attenuate.
*
* <p>This filter is stable for time constants greater than zero.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ public static Rotation2d fromRotations(double rotations) {
}

/**
* Adds two rotations together, with the result being bounded between -pi and pi.
* Adds two rotations together, with the result being bounded between -π and π.
*
* <p>For example, <code>Rotation2d.fromDegrees(30).plus(Rotation2d.fromDegrees(60))</code> equals
* <code>Rotation2d(Math.PI/2.0)</code>
Expand Down Expand Up @@ -251,7 +251,7 @@ public Angle getMeasure() {
* Returns the radian value of the Rotation2d.
*
* @return The radian value of the Rotation2d.
* @see edu.wpi.first.math.MathUtil#angleModulus(double) to constrain the angle within (-pi, pi]
* @see edu.wpi.first.math.MathUtil#angleModulus(double) to constrain the angle within (-π, π]
*/
@JsonProperty
public double getRadians() {
Expand Down
2 changes: 1 addition & 1 deletion wpimath/src/main/native/include/frc/MathUtil.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ constexpr bool IsNear(T expected, T actual, T tolerance, T min, T max) {
}

/**
* Wraps an angle to the range -pi to pi radians (-180 to 180 degrees).
* Wraps an angle to the range -π to π radians (-180 to 180 degrees).
*
* @param angle Angle to wrap.
*/
Expand Down
4 changes: 2 additions & 2 deletions wpimath/src/main/native/include/frc/filter/LinearFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class LinearFilter {
* y[n] = (1 - gain) x[n] + gain y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* Note: T = 1 / (2 pi f) where f is the cutoff frequency in Hz, the frequency
* Note: T = 1 / (2πf) where f is the cutoff frequency in Hz, the frequency
* above which the input starts to attenuate.
*
* This filter is stable for time constants greater than zero.
Expand All @@ -138,7 +138,7 @@ class LinearFilter {
* y[n] = gain x[n] + (-gain) x[n-1] + gain y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* Note: T = 1 / (2 pi f) where f is the cutoff frequency in Hz, the frequency
* Note: T = 1 / (2πf) where f is the cutoff frequency in Hz, the frequency
* below which the input starts to attenuate.
*
* This filter is stable for time constants greater than zero.
Expand Down
6 changes: 3 additions & 3 deletions wpimath/src/main/native/include/frc/geometry/Rotation2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ class WPILIB_DLLEXPORT Rotation2d {
}

/**
* Adds two rotations together, with the result being bounded between -pi and
* pi.
* Adds two rotations together, with the result being bounded between -π and
* π.
*
* For example, <code>Rotation2d{30_deg} + Rotation2d{60_deg}</code> equals
* <code>Rotation2d{units::radian_t{std::numbers::pi/2.0}}</code>
Expand Down Expand Up @@ -158,7 +158,7 @@ class WPILIB_DLLEXPORT Rotation2d {
* Returns the radian value of the rotation.
*
* @return The radian value of the rotation.
* @see AngleModulus to constrain the angle within (-pi, pi]
* @see AngleModulus to constrain the angle within (-π, π]
*/
constexpr units::radian_t Radians() const { return m_value; }

Expand Down

0 comments on commit dfd1084

Please sign in to comment.