Package edu.wpi.first.wpilibj.xrp
Class XRPGyro
java.lang.Object
edu.wpi.first.wpilibj.xrp.XRPGyro
Use a rate gyro to return the robots heading relative to a starting position.
This class is for the XRP onboard gyro, and will only work in simulation/XRP mode. Only one instance of a XRPGyro is supported.
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionvoid
close()
Close out the SimDevice.double
getAngle()
Return the actual angle in degrees that the robot is currently facing.double
Get the currently reported angle around the X-axis.double
Get the currently reported angle around the X-axis.double
Get the currently reported angle around the Z-axis.double
getRate()
Return the rate of rotation of the gyrodouble
getRateX()
Get the rate of turn in degrees-per-second around the X-axis.double
getRateY()
Get the rate of turn in degrees-per-second around the Y-axis.double
getRateZ()
Get the rate of turn in degrees-per-second around the Z-axis.Gets the angle the robot is facing.void
reset()
Reset the gyro angles to 0.
-
Constructor Details
-
XRPGyro
public XRPGyro()Constructs an XRPGyro.Only one instance of a XRPGyro is supported.
-
-
Method Details
-
getRateX
Get the rate of turn in degrees-per-second around the X-axis.- Returns:
- rate of turn in degrees-per-second
-
getRateY
Get the rate of turn in degrees-per-second around the Y-axis.- Returns:
- rate of turn in degrees-per-second
-
getRateZ
Get the rate of turn in degrees-per-second around the Z-axis.- Returns:
- rate of turn in degrees-per-second
-
getAngleX
Get the currently reported angle around the X-axis.- Returns:
- current angle around X-axis in degrees
-
getAngleY
Get the currently reported angle around the X-axis.- Returns:
- current angle around Y-axis in degrees
-
getAngleZ
Get the currently reported angle around the Z-axis.- Returns:
- current angle around Z-axis in degrees
-
reset
Reset the gyro angles to 0. -
getAngle
Return the actual angle in degrees that the robot is currently facing.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.
- Returns:
- the current heading of the robot in degrees.
-
getRotation2d
Gets the angle the robot is facing.- Returns:
- A Rotation2d with the current heading.
-
getRate
Return the rate of rotation of the gyroThe rate is based on the most recent reading of the gyro.
- Returns:
- the current rate in degrees per second
-
close
Close out the SimDevice.
-