Class AnalogGyro
- All Implemented Interfaces:
Sendable,AutoCloseable
This class is for gyro sensors that connect to an analog input.
-
Constructor Summary
ConstructorsConstructorDescriptionAnalogGyro(int channel) Gyro constructor using the channel number.AnalogGyro(int channel, int center, double offset) Gyro constructor using the channel number along with parameters for presetting the center and offset values.AnalogGyro(AnalogInput channel) Gyro constructor with a precreated analog channel object.AnalogGyro(AnalogInput channel, int center, double offset) Gyro constructor with a precreated analog channel object along with parameters for presetting the center and offset values. -
Method Summary
Modifier and TypeMethodDescriptionvoidCalibrate the gyro by running for a number of samples and computing the center value.voidclose()Delete (free) the accumulator and the analog components used for the gyro.Gets the analog input for the gyro.doublegetAngle()Return the heading of the robot in degrees.intReturn the gyro center value set during calibration to use as a future preset.doubleReturn the gyro offset value set during calibration to use as a future preset.doublegetRate()Return the rate of rotation of the gyro.Return the heading of the robot as aRotation2d.voidinitSendable(SendableBuilder builder) Initializes thisSendableobject.voidreset()Reset the gyro.voidsetDeadband(double volts) Set the size of the neutral zone.voidsetSensitivity(double voltsPerDegreePerSecond) Set the gyro sensitivity.
-
Constructor Details
-
AnalogGyro
Gyro constructor using the channel number.- Parameters:
channel- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.
-
AnalogGyro
Gyro constructor with a precreated analog channel object. Use this constructor when the analog channel needs to be shared.- Parameters:
channel- The AnalogInput object that the gyro is connected to. Gyros can only be used on on-board channels 0-1.
-
AnalogGyro
Gyro constructor using the channel number along with parameters for presetting the center and offset values. Bypasses calibration.- Parameters:
channel- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.center- Preset uncalibrated value to use as the accumulator center value.offset- Preset uncalibrated value to use as the gyro offset.
-
AnalogGyro
Gyro constructor with a precreated analog channel object along with parameters for presetting the center and offset values. Bypasses calibration.- Parameters:
channel- The analog channel the gyro is connected to. Gyros can only be used on on-board channels 0-1.center- Preset uncalibrated value to use as the accumulator center value.offset- Preset uncalibrated value to use as the gyro offset.
-
-
Method Details
-
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.
-
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.
-
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 accumulator and the analog components used for the gyro.- Specified by:
closein 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
-
getOffset
Return the gyro offset value set during calibration to use as a future preset.- Returns:
- the current offset value
-
getCenter
Return the gyro center value set during calibration to use as a future preset.- Returns:
- the current center value
-
setSensitivity
Set the gyro sensitivity. This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent calculations to allow the code to work with multiple gyros. This value is typically found in the gyro datasheet.- Parameters:
voltsPerDegreePerSecond- The sensitivity in Volts/degree/second.
-
setDeadband
Set the size of the neutral zone. Any voltage from the gyro less than this amount from the center is considered stationary. Setting a deadband will decrease the amount of drift when the gyro isn't rotating, but will make it less accurate.- Parameters:
volts- The size of the deadband in volts
-
getAnalogInput
Gets the analog input for the gyro.- Returns:
- AnalogInput
-
initSendable
Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-