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

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

Public Member Functions

 WPI_Pigeon2 (int deviceNumber, String canbus)
 
 WPI_Pigeon2 (int deviceNumber)
 
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.Pigeon2
 Pigeon2 (int deviceNumber, String canbus)
 
 Pigeon2 (int deviceNumber)
 
ErrorCode configMountPose (double yaw, double pitch, double roll, int timeoutMs)
 
ErrorCode configMountPose (double yaw, double pitch, double roll)
 
ErrorCode configMountPoseYaw (double yaw, int timeoutMs)
 
ErrorCode configMountPoseYaw (double yaw)
 
ErrorCode configMountPosePitch (double pitch, int timeoutMs)
 
ErrorCode configMountPosePitch (double pitch)
 
ErrorCode configMountPoseRoll (double roll, int timeoutMs)
 
ErrorCode configMountPoseRoll (double roll)
 
ErrorCode configEnableCompass (boolean enable, int timeoutMs)
 
ErrorCode configEnableCompass (boolean enable)
 
ErrorCode configDisableTemperatureCompensation (boolean disable, int timeoutMs)
 
ErrorCode configDisableTemperatureCompensation (boolean disable)
 
ErrorCode configDisableNoMotionCalibration (boolean disable, int timeoutMs)
 
ErrorCode configDisableNoMotionCalibration (boolean disable)
 
ErrorCode zeroGyroBiasNow (int timeoutMs)
 
ErrorCode zeroGyroBiasNow ()
 
ErrorCode configAllSettings (Pigeon2Configuration settings, int timeoutMs)
 
ErrorCode configAllSettings (Pigeon2Configuration settings)
 
ErrorCode getGravityVector (double[] gravVector)
 
ErrorCode getFaults (Pigeon2_Faults toFill)
 
ErrorCode getStickyFaults (Pigeon2_Faults toFill)
 
void getAllConfigs (Pigeon2Configuration allConfigs, int timeoutMs)
 
void getAllConfigs (Pigeon2Configuration allConfigs)
 
- 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_Pigeon2() [1/2]

com.ctre.phoenix.sensors.WPI_Pigeon2.WPI_Pigeon2 ( int  deviceNumber,
String  canbus 
)
inline

Constructor for Pigeon 2.

Parameters
deviceNumberdevice ID of Pigeon 2
canbusName of the CANbus; can be a CANivore device name or serial number. Pass in nothing or "rio" to use the roboRIO.

◆ WPI_Pigeon2() [2/2]

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

Constructor for Pigeon 2.

Parameters
deviceNumberdevice ID of Pigeon 2

Member Function Documentation

◆ calibrate()

void com.ctre.phoenix.sensors.WPI_Pigeon2.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: