Skip to content

Commit

Permalink
[xrp] Cleanup gyro docs (#7033)
Browse files Browse the repository at this point in the history
  • Loading branch information
spacey-sooty authored Sep 7, 2024
1 parent 2aef60d commit 80f3813
Showing 1 changed file with 23 additions and 0 deletions.
23 changes: 23 additions & 0 deletions xrpVendordep/src/main/java/edu/wpi/first/wpilibj/xrp/XRPGyro.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,12 @@
import edu.wpi.first.hal.SimDevice.Direction;
import edu.wpi.first.hal.SimDouble;

/**
* Use a rate gyro to return the robots heading relative to a starting position.
*
* <p>This class is for the XRP onboard gyro, and will only work in simulation/XRP mode. Only one
* instance of a XRPGyro is supported.
*/
public class XRPGyro {
private final SimDevice m_simDevice;
private final SimDouble m_simRateX;
Expand Down Expand Up @@ -130,10 +136,27 @@ public void reset() {
}
}

/**
* Return the actual angle in degrees that the robot is currently facing.
*
* <p>The angle is based on integration of the returned rate form the gyro. The angle is
* continuous, that is, it will continue from 360->361 degrees. This allows algorithms that
* wouldn't want to see a discontinuity in the gyro output as it sweeps from 360 to 0 on the
* second time around.
*
* @return the current heading of the robot in degrees.
*/
public double getAngle() {
return getAngleZ();
}

/**
* Return the rate of rotation of the gyro
*
* <p>The rate is based on the most recent reading of the gyro.
*
* @return the current rate in degrees per second
*/
public double getRate() {
return getRateZ();
}
Expand Down

0 comments on commit 80f3813

Please sign in to comment.