CTRE_Phoenix 5.20.2
com.ctre.phoenix.sensors.WPI_PigeonIMU Class Reference

Inherits com.ctre.phoenix.sensors.PigeonIMU, Sendable, and Gyro.

Public Member Functions

 WPI_PigeonIMU (int deviceNumber)
 
 WPI_PigeonIMU (TalonSRX talon)
 
void close ()
 
void calibrate ()
 
void reset ()
 
double getAngle ()
 
double getRate ()
 
Rotation2d getRotation2d ()
 
void initSendable (SendableBuilder builder)
 
- Public Member Functions inherited from com.ctre.phoenix.sensors.PigeonIMU
 PigeonIMU (int deviceNumber)
 
 PigeonIMU (TalonSRX talonSrx)
 
ErrorCode setFusedHeading (double angleDeg, int timeoutMs)
 
ErrorCode setFusedHeading (double angleDeg)
 
ErrorCode addFusedHeading (double angleDeg, int timeoutMs)
 
ErrorCode addFusedHeading (double angleDeg)
 
ErrorCode setFusedHeadingToCompass (int timeoutMs)
 
ErrorCode setFusedHeadingToCompass ()
 
ErrorCode setTemperatureCompensationDisable (boolean bTempCompDisable, int timeoutMs)
 
ErrorCode setTemperatureCompensationDisable (boolean bTempCompDisable)
 
ErrorCode setCompassDeclination (double angleDegOffset, int timeoutMs)
 
ErrorCode setCompassDeclination (double angleDegOffset)
 
ErrorCode setCompassAngle (double angleDeg, int timeoutMs)
 
ErrorCode setCompassAngle (double angleDeg)
 
ErrorCode enterCalibrationMode (CalibrationMode calMode, int timeoutMs)
 
ErrorCode enterCalibrationMode (CalibrationMode calMode)
 
ErrorCode getGeneralStatus (GeneralStatus toFill)
 
PigeonState getState ()
 
double getFusedHeading (FusionStatus toFill)
 
double getFusedHeading ()
 
ErrorCode getAccelerometerAngles (double[] tiltAngles)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs)
 
ErrorCode configFactoryDefault (int timeoutMs)
 
ErrorCode configFactoryDefault ()
 
ErrorCode getFaults (PigeonIMU_Faults toFill)
 
ErrorCode getStickyFaults (PigeonIMU_Faults toFill)
 
- Public Member Functions inherited from com.ctre.phoenix.sensors.BasePigeon
 BasePigeon (int deviceNumber, String version, String canbus)
 
 BasePigeon (int deviceNumber, String version)
 
ErrorCode DestroyObject ()
 
BasePigeonSimCollection getSimCollection ()
 
ErrorCode setYaw (double angleDeg, int timeoutMs)
 
ErrorCode setYaw (double angleDeg)
 
ErrorCode addYaw (double angleDeg, int timeoutMs)
 
ErrorCode addYaw (double angleDeg)
 
ErrorCode setYawToCompass (int timeoutMs)
 
ErrorCode setYawToCompass ()
 
ErrorCode setAccumZAngle (double angleDeg, int timeoutMs)
 
ErrorCode setAccumZAngle (double angleDeg)
 
ErrorCode getLastError ()
 
ErrorCode get6dQuaternion (double[] wxyz)
 
ErrorCode getYawPitchRoll (double[] ypr_deg)
 
double getYaw ()
 
double getPitch ()
 
double getRoll ()
 
ErrorCode getAccumGyro (double[] xyz_deg)
 
double getAbsoluteCompassHeading ()
 
double getCompassHeading ()
 
double getCompassFieldStrength ()
 
double getTemp ()
 
int getUpTime ()
 
ErrorCode getRawMagnetometer (short[] rm_xyz)
 
ErrorCode getBiasedMagnetometer (short[] bm_xyz)
 
ErrorCode getBiasedAccelerometer (short[] ba_xyz)
 
ErrorCode getRawGyro (double[] xyz_dps)
 
int getResetCount ()
 
int getResetFlags ()
 
int getFirmwareVersion ()
 
boolean hasResetOccurred ()
 
ErrorCode configSetCustomParam (int newValue, int paramIndex, int timeoutMs)
 
ErrorCode configSetCustomParam (int newValue, int paramIndex)
 
int configGetCustomParam (int paramIndex, int timoutMs)
 
int configGetCustomParam (int paramIndex)
 
ErrorCode configSetParameter (ParamEnum param, double value, int subValue, int ordinal, int timeoutMs)
 
ErrorCode configSetParameter (ParamEnum param, double value, int subValue, int ordinal)
 
ErrorCode configSetParameter (int param, double value, int subValue, int ordinal, int timeoutMs)
 
ErrorCode configSetParameter (int param, double value, int subValue, int ordinal)
 
double configGetParameter (ParamEnum param, int ordinal, int timeoutMs)
 
double configGetParameter (ParamEnum param, int ordinal)
 
double configGetParameter (int param, int ordinal, int timeoutMs)
 
double configGetParameter (int param, int ordinal)
 
ErrorCode setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs)
 
ErrorCode setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs)
 
ErrorCode setStatusFramePeriod (int statusFrame, int periodMs, int timeoutMs)
 
ErrorCode setStatusFramePeriod (int statusFrame, int periodMs)
 
int getStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs)
 
int getStatusFramePeriod (PigeonIMU_StatusFrame frame)
 
ErrorCode setControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 
ErrorCode setControlFramePeriod (int frame, int periodMs)
 
ErrorCode clearStickyFaults (int timeoutMs)
 
ErrorCode clearStickyFaults ()
 
int getDeviceID ()
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs)
 
ErrorCode configFactoryDefault (int timeoutMs)
 
ErrorCode configFactoryDefault ()
 
long getHandle ()
 

Additional Inherited Members

- Protected Member Functions inherited from com.ctre.phoenix.sensors.BasePigeon
 BasePigeon (long handle)
 

Constructor & Destructor Documentation

◆ WPI_PigeonIMU() [1/2]

com.ctre.phoenix.sensors.WPI_PigeonIMU.WPI_PigeonIMU ( int  deviceNumber)
inline

Constructor for Pigeon IMU.

Parameters
deviceNumberdevice ID of Pigeon IMU

◆ WPI_PigeonIMU() [2/2]

com.ctre.phoenix.sensors.WPI_PigeonIMU.WPI_PigeonIMU ( TalonSRX  talon)
inline

Construtor for WPI_PigeonIMU.

Parameters
talonThe Talon SRX ribbon-cabled to Pigeon.

Member Function Documentation

◆ calibrate()

void com.ctre.phoenix.sensors.WPI_PigeonIMU.calibrate ( )
inline

This function does nothing, it exists to satisfy the WPILib Gyro interface.

Pigeon does calibration on boot and any one-time calibrations (like temperature) are done via Phoenix Tuner.


The documentation for this class was generated from the following file: