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

Inherits com.ctre.phoenix.sensors.BasePigeon.

Inherited by com.ctre.phoenix.sensors.WPI_Pigeon2.

Public Member Functions

 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)
 

Detailed Description

Pigeon 2 Class. Class supports communicating over CANbus.


// Example usage of a Pigeon 2
Pigeon2 pigeon = new Pigeon2(0); // creates a new Pigeon2 with ID 0

Pigeon2Configuration config = new Pigeon2Configuration();
// set mount pose as rolled 90 degrees counter-clockwise
config.MountPoseYaw = 0;
config.MountPosePitch = 0;
config.MountPoseRoll = 90;
pigeon.configAllSettings(config);

System.out.println(pigeon.getYaw()); // prints the yaw of the Pigeon
System.out.println(pigeon.getPitch()); // prints the pitch of the Pigeon
System.out.println(pigeon.getRoll()); // prints the roll of the Pigeon

double gravityVec[] = new double[3];
pigeon.getGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2

ErrorCode error = pigeon.getLastError(); // gets the last error generated by the Pigeon
Pigeon2_Faults faults = new Pigeon2_Faults();
ErrorCode faultsError = pigeon.getFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated

Constructor & Destructor Documentation

◆ Pigeon2() [1/2]

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

Create a Pigeon object that communicates with Pigeon on CAN Bus.

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]
canbusName of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number

◆ Pigeon2() [2/2]

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

Create a Pigeon object that communicates with Pigeon on CAN Bus.

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]

Member Function Documentation

◆ configAllSettings() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configAllSettings ( Pigeon2Configuration  settings)
inline

Configures all persistent settings.

Parameters
allConfigsObject with all of the persistant settings
Returns
Error Code generated by function. 0 indicates no error.

◆ configAllSettings() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configAllSettings ( Pigeon2Configuration  settings,
int  timeoutMs 
)
inline

Configures all persistent settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
Returns
Error Code generated by function. 0 indicates no error.

◆ configDisableNoMotionCalibration() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configDisableNoMotionCalibration ( boolean  disable)
inline

Disables the no-motion calibration from Pigeon2

Parameters
disableBoolean to disable/enable no-motion calibration
Returns
ErrorCode Status of the config response

◆ configDisableNoMotionCalibration() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configDisableNoMotionCalibration ( boolean  disable,
int  timeoutMs 
)
inline

Disables the no-motion calibration from Pigeon2

Parameters
disableBoolean to disable/enable no-motion calibration
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode Status of the config response

◆ configDisableTemperatureCompensation() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configDisableTemperatureCompensation ( boolean  disable)
inline

Disables temperature compensation from Pigeon2.

Parameters
disableBoolean to disable/enable temperature compensation
Returns
ErrorCode Status of the config response

◆ configDisableTemperatureCompensation() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configDisableTemperatureCompensation ( boolean  disable,
int  timeoutMs 
)
inline

Disables temperature compensation from Pigeon2.

Parameters
disableBoolean to disable/enable temperature compensation
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode Status of the config response

◆ configEnableCompass() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configEnableCompass ( boolean  enable)
inline

Enables the magnetometer fusion for Pigeon2. This is not recommended for FRC use

Parameters
enableBoolean to enable/disable magnetometer fusion
Returns
ErrorCode Status of the config response

◆ configEnableCompass() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configEnableCompass ( boolean  enable,
int  timeoutMs 
)
inline

Enables the magnetometer fusion for Pigeon2. This is not recommended for FRC use

Parameters
enableBoolean to enable/disable magnetometer fusion
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode Status of the config response

◆ configMountPose() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPose ( double  yaw,
double  pitch,
double  roll 
)
inline

Configure the mounting pose of the Pigeon2.

This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.

This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.

If the pigeon is relatively flat and pointed forward, this is not needed.

Examples:

If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.

If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.

Parameters
yawYaw angle needed to reach the current orientation in degrees.
pitchPitch angle needed to reach the current orientation in degrees.
rollRoll angle needed to reach the current orientation in degrees.
Returns
Worst error code of all config sets.

◆ configMountPose() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPose ( double  yaw,
double  pitch,
double  roll,
int  timeoutMs 
)
inline

Configure the mounting pose of the Pigeon2.

This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.

This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.

If the pigeon is relatively flat and pointed forward, this is not needed.

Examples:

If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.

If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.

Parameters
yawYaw angle needed to reach the current orientation in degrees.
pitchPitch angle needed to reach the current orientation in degrees.
rollRoll angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
Worst error code of all config sets.

◆ configMountPosePitch() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPosePitch ( double  pitch)
inline

Configure the mounting pose Pitch of the Pigeon2. See configMountPose(double, double, double)

Parameters
pitchPitch angle needed to reach the current orientation in degrees.
Returns
ErrorCode of configSet

◆ configMountPosePitch() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPosePitch ( double  pitch,
int  timeoutMs 
)
inline

Configure the mounting pose Pitch of the Pigeon2. See configMountPose(double, double, double, int)

Parameters
pitchPitch angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ configMountPoseRoll() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPoseRoll ( double  roll)
inline

Configure the mounting pose Roll of the Pigeon2. See configMountPose(double, double, double)

Parameters
rollRoll angle needed to reach the current orientation in degrees.
Returns
ErrorCode of configSet

◆ configMountPoseRoll() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPoseRoll ( double  roll,
int  timeoutMs 
)
inline

Configure the mounting pose Roll of the Pigeon2. See configMountPose(double, double, double, int)

Parameters
rollRoll angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ configMountPoseYaw() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPoseYaw ( double  yaw)
inline

Configure the mounting pose Yaw of the Pigeon2. See configMountPose(double, double, double)

Parameters
yawYaw angle needed to reach the current orientation in degrees.
Returns
ErrorCode of configSet

◆ configMountPoseYaw() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.configMountPoseYaw ( double  yaw,
int  timeoutMs 
)
inline

Configure the mounting pose Yaw of the Pigeon2. See configMountPose(double, double, double, int)

Parameters
yawYaw angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ getAllConfigs() [1/2]

void com.ctre.phoenix.sensors.Pigeon2.getAllConfigs ( Pigeon2Configuration  allConfigs)
inline

Gets all persistant settings.

Parameters
allConfigsObject with all of the persistant settings

◆ getAllConfigs() [2/2]

void com.ctre.phoenix.sensors.Pigeon2.getAllConfigs ( Pigeon2Configuration  allConfigs,
int  timeoutMs 
)
inline

Gets all persistant settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

◆ getFaults()

ErrorCode com.ctre.phoenix.sensors.Pigeon2.getFaults ( Pigeon2_Faults  toFill)
inline

Gets the fault status

Parameters
toFillContainer for fault statuses.
Returns
Error Code generated by function. 0 indicates no error.

◆ getGravityVector()

ErrorCode com.ctre.phoenix.sensors.Pigeon2.getGravityVector ( double[]  gravVector)
inline

Get the Gravity Vector.

This provides a vector that points toward ground. This is useful for applications like an arm, where the z-value of the gravity vector corresponds to the feed-forward needed to hold the arm steady. The gravity vector is calculated after the mount pose, so if the pigeon is where it was mounted, the gravity vector is {0, 0, 1}.

Parameters
gravVectorPass in a double array of size 3 to get the gravity vector
Returns
Errorcode of getter

◆ getStickyFaults()

ErrorCode com.ctre.phoenix.sensors.Pigeon2.getStickyFaults ( Pigeon2_Faults  toFill)
inline

Gets the sticky fault status

Parameters
toFillContainer for sticky fault statuses.
Returns
Error Code generated by function. 0 indicates no error.

◆ zeroGyroBiasNow() [1/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.zeroGyroBiasNow ( )
inline

Performs an offset calibration on gyro bias

Returns
ErrorCode Status of the config response

◆ zeroGyroBiasNow() [2/2]

ErrorCode com.ctre.phoenix.sensors.Pigeon2.zeroGyroBiasNow ( int  timeoutMs)
inline

Performs an offset calibration on gyro bias

Parameters
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode Status of the config response

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