Interface Gyro
- All Superinterfaces:
AutoCloseable
- All Known Implementing Classes:
ADXRS450_Gyro
,AnalogGyro
public interface Gyro extends AutoCloseable
-
Method Summary
Modifier and Type Method Description void
calibrate()
Calibrate the gyro.double
getAngle()
Return the heading of the robot in degrees.double
getRate()
Return the rate of rotation of the gyro.default Rotation2d
getRotation2d()
Return the heading of the robot as aRotation2d
.void
reset()
Reset the gyro.
-
Method Details
-
calibrate
void calibrate()Calibrate the gyro. It's important to make sure that the robot is not moving while the calibration is in progress, this is typically done when the robot is first turned on while it's sitting at rest before the match starts. -
reset
void reset()Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant drift in the gyro, and it needs to be recalibrated after it has been running. -
getAngle
double getAngle()Return the heading of the robot in degrees.The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
The angle is expected to increase as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.
This heading is based on integration of the returned rate from the gyro.
- Returns:
- the current heading of the robot in degrees.
-
getRate
double getRate()Return the rate of rotation of the gyro.The rate is based on the most recent reading of the gyro analog value
The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.
- Returns:
- the current rate in degrees per second
-
getRotation2d
Return the heading of the robot as aRotation2d
.The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
The angle is expected to increase as the gyro turns counterclockwise when looked at from the top. It needs to follow the NWU axis convention.
This heading is based on integration of the returned rate from the gyro.
- Returns:
- the current heading of the robot as a
Rotation2d
.
-