Class ADXRS450_Gyro
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class ADXRS450_Gyro extends Object implements Sendable, AutoCloseable
This class is for the digital ADXRS450 gyro sensor that connects via SPI. Only one instance of an ADXRS Gyro is supported.
-
Constructor Summary
Constructors Constructor Description ADXRS450_Gyro()
Constructor.ADXRS450_Gyro(SPI.Port port)
Constructor. -
Method Summary
Modifier and Type Method Description void
calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.void
close()
Delete (free) the spi port used for the gyro and stop accumulating.double
getAngle()
Return the heading of the robot in degrees.int
getPort()
Get the SPI port number.double
getRate()
Return the rate of rotation of the gyro.Rotation2d
getRotation2d()
Return the heading of the robot as aRotation2d
.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.boolean
isConnected()
Determine if the gyro is connected.void
reset()
Reset the gyro.
-
Constructor Details
-
ADXRS450_Gyro
public ADXRS450_Gyro()Constructor. Uses the onboard CS0. -
ADXRS450_Gyro
Constructor.- Parameters:
port
- The SPI port that the gyro is connected to
-
-
Method Details
-
isConnected
Determine if the gyro is connected.- Returns:
- true if it is connected, false otherwise.
-
calibrate
Calibrate the gyro by running for a number of samples and computing the center value. Then use the center value as the Accumulator center value for subsequent measurements.It's important to make sure that the robot is not moving while the centering calculations are in progress, this is typically done when the robot is first turned on while it's sitting at rest before the competition starts.
-
getPort
Get the SPI port number.- Returns:
- The SPI port number.
-
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.
-
close
Delete (free) the spi port used for the gyro and stop accumulating.- Specified by:
close
in interfaceAutoCloseable
-
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
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
.
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-