Package edu.wpi.first.wpilibj.romi
Class RomiGyro
java.lang.Object
edu.wpi.first.wpilibj.romi.RomiGyro
Use a rate gyro to return the robots heading relative to a starting position.
This class is for the Romi onboard gyro, and will only work in simulation/Romi mode. Only one instance of a RomiGyro is supported.
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoidclose()Close out the SimDevice.doublegetAngle()Return the actual angle in degrees that the robot is currently facing.doubleGet the currently reported angle around the X-axis.doubleGet the currently reported angle around the X-axis.doubleGet the currently reported angle around the Z-axis.doublegetRate()Return the rate of rotation of the gyrodoublegetRateX()Get the rate of turn in degrees-per-second around the X-axis.doublegetRateY()Get the rate of turn in degrees-per-second around the Y-axis.doublegetRateZ()Get the rate of turn in degrees-per-second around the Z-axis.voidreset()Reset the gyro angles to 0.
-
Constructor Details
-
RomiGyro
public RomiGyro()Create a new RomiGyro.
-
-
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.
-
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.
-