Class ADXRS450_Gyro
- java.lang.Object
-
- edu.wpi.first.wpilibj.ADXRS450_Gyro
-
- All Implemented Interfaces:
Sendable
,Gyro
,AutoCloseable
public class ADXRS450_Gyro extends Object implements Gyro, Sendable
Use a rate gyro to return the robots heading relative to a starting position. The Gyro class tracks the robots heading based on the starting position. As the robot rotates the new heading is computed by integrating the rate of rotation returned by the sensor. When the class is instantiated, it does a short calibration routine where it samples the gyro while at rest to determine the default offset. This is subtracted from each sample to determine the heading.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
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
calibrate()
Calibrate the gyro.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.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.boolean
isConnected()
Determine if the gyro is connected.void
reset()
Reset the gyro.-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.interfaces.Gyro
getRotation2d
-
-
-
-
Constructor Detail
-
ADXRS450_Gyro
public ADXRS450_Gyro()
Constructor. Uses the onboard CS0.
-
ADXRS450_Gyro
public ADXRS450_Gyro(SPI.Port port)
Constructor.- Parameters:
port
- The SPI port that the gyro is connected to
-
-
Method Detail
-
isConnected
public boolean isConnected()
Determine if the gyro is connected.- Returns:
- true if it is connected, false otherwise.
-
calibrate
public void calibrate()
Description copied from interface:Gyro
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.
-
getPort
public int getPort()
Get the SPI port number.- Returns:
- The SPI port number.
-
reset
public void reset()
Description copied from interface:Gyro
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
public void close()
Delete (free) the spi port used for the gyro and stop accumulating.- Specified by:
close
in interfaceAutoCloseable
-
getAngle
public double getAngle()
Description copied from interface:Gyro
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.
-
getRate
public double getRate()
Description copied from interface:Gyro
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.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-