Class WPI_PigeonIMU
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class WPI_PigeonIMU extends PigeonIMU implements Sendable, AutoCloseable
-
Nested Class Summary
Nested classes/interfaces inherited from class com.ctre.phoenix.sensors.PigeonIMU
PigeonIMU.CalibrationMode, PigeonIMU.FusionStatus, PigeonIMU.GeneralStatus, PigeonIMU.PigeonState
-
Constructor Summary
Constructors Constructor Description WPI_PigeonIMU(int deviceNumber)
Constructor for Pigeon IMU.WPI_PigeonIMU(TalonSRX talon)
Construtor for WPI_PigeonIMU. -
Method Summary
Modifier and Type Method Description void
close()
double
getAngle()
Returns the heading of the robot in degrees.double
getRate()
Returns the rate of rotation of the Pigeon IMU.Rotation2d
getRotation2d()
Returns the heading of the robot as aRotation2d
.void
initSendable(SendableBuilder builder)
void
reset()
Resets the Pigeon IMU to a heading of zero.Methods inherited from class com.ctre.phoenix.sensors.PigeonIMU
addFusedHeading, addFusedHeading, configAllSettings, configAllSettings, configFactoryDefault, configFactoryDefault, enterCalibrationMode, enterCalibrationMode, getAccelerometerAngles, getAllConfigs, getAllConfigs, getFaults, getFusedHeading, getFusedHeading, getGeneralStatus, getState, getStickyFaults, setCompassAngle, setCompassAngle, setCompassDeclination, setCompassDeclination, setFusedHeading, setFusedHeading, setFusedHeadingToCompass, setFusedHeadingToCompass, setTemperatureCompensationDisable, setTemperatureCompensationDisable
Methods inherited from class com.ctre.phoenix.sensors.BasePigeon
addYaw, addYaw, clearStickyFaults, clearStickyFaults, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, DestroyObject, get6dQuaternion, getAbsoluteCompassHeading, getAccumGyro, getBiasedAccelerometer, getBiasedMagnetometer, getCompassFieldStrength, getCompassHeading, getDeviceID, getFirmwareVersion, getHandle, getLastError, getPitch, getRawGyro, getRawMagnetometer, getResetCount, getResetFlags, getRoll, getSimCollection, getStatusFramePeriod, getStatusFramePeriod, getTemp, getUpTime, getYaw, getYawPitchRoll, hasResetOccurred, setAccumZAngle, setAccumZAngle, setControlFramePeriod, setControlFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setYaw, setYaw, setYawToCompass, setYawToCompass
-
Constructor Details
-
WPI_PigeonIMU
Constructor for Pigeon IMU.- Parameters:
deviceNumber
- device ID of Pigeon IMU
-
WPI_PigeonIMU
Construtor for WPI_PigeonIMU.- Parameters:
talon
- The Talon SRX ribbon-cabled to Pigeon.
-
-
Method Details
-
close
- Specified by:
close
in interfaceAutoCloseable
-
reset
Resets the Pigeon IMU 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
Returns the heading of the robot in degrees.The angle increases as the Pigeon IMU turns clockwise when looked at from the top. This follows the NED axis convention.
The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.
- Returns:
- The current heading of the robot in degrees
-
getRate
Returns the rate of rotation of the Pigeon IMU.The rate is positive as the Pigeon IMU turns clockwise when looked at from the top.
- Returns:
- The current rate in degrees per second
-
getRotation2d
Returns the heading of the robot as aRotation2d
.The angle increases as the Pigeon IMU turns counterclockwise when looked at from the top. This follows the NWU axis convention.
The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.
- Returns:
- The current heading of the robot as a
Rotation2d
-
initSendable
- Specified by:
initSendable
in interfaceSendable
-