Class Pigeon2
- Direct Known Subclasses:
WPI_Pigeon2
public class Pigeon2 extends BasePigeon
// 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
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
Pigeon2.AxisDirection
Enumerations for what primary axis to talk about Positive indicates in the direction, negative indicates in the opposite direction -
Constructor Summary
-
Method Summary
Modifier and Type Method Description ErrorCode
configAllSettings(Pigeon2Configuration settings)
Configures all persistent settings.ErrorCode
configAllSettings(Pigeon2Configuration settings, int timeoutMs)
Configures all persistent settings.ErrorCode
configDisableNoMotionCalibration(boolean disable)
Disables the no-motion calibration from Pigeon2ErrorCode
configDisableNoMotionCalibration(boolean disable, int timeoutMs)
Disables the no-motion calibration from Pigeon2ErrorCode
configDisableTemperatureCompensation(boolean disable)
Disables temperature compensation from Pigeon2.ErrorCode
configDisableTemperatureCompensation(boolean disable, int timeoutMs)
Disables temperature compensation from Pigeon2.ErrorCode
configEnableCompass(boolean enable)
Enables the magnetometer fusion for Pigeon2.ErrorCode
configEnableCompass(boolean enable, int timeoutMs)
Enables the magnetometer fusion for Pigeon2.ErrorCode
configMountPose(double yaw, double pitch, double roll)
Configure the mounting pose of the Pigeon2.ErrorCode
configMountPose(double yaw, double pitch, double roll, int timeoutMs)
Configure the mounting pose of the Pigeon2.ErrorCode
configMountPose(Pigeon2.AxisDirection forward, Pigeon2.AxisDirection up)
Configure the Mount Pose using the primary axis.ErrorCode
configMountPose(Pigeon2.AxisDirection forward, Pigeon2.AxisDirection up, int timeoutMs)
Configure the Mount Pose using the primary axis.ErrorCode
configMountPosePitch(double pitch)
Configure the mounting pose Pitch of the Pigeon2.ErrorCode
configMountPosePitch(double pitch, int timeoutMs)
Configure the mounting pose Pitch of the Pigeon2.ErrorCode
configMountPoseRoll(double roll)
Configure the mounting pose Roll of the Pigeon2.ErrorCode
configMountPoseRoll(double roll, int timeoutMs)
Configure the mounting pose Roll of the Pigeon2.ErrorCode
configMountPoseYaw(double yaw)
Configure the mounting pose Yaw of the Pigeon2.ErrorCode
configMountPoseYaw(double yaw, int timeoutMs)
Configure the mounting pose Yaw of the Pigeon2.ErrorCode
configXAxisGyroError(double err)
Configures the X Axis Gyroscope Error for 1 rotationErrorCode
configXAxisGyroError(double err, int timeoutMs)
Configures the X Axis Gyroscope Error for 1 rotationErrorCode
configYAxisGyroError(double err)
Configures the Y Axis Gyroscope Error for 1 rotationErrorCode
configYAxisGyroError(double err, int timeoutMs)
Configures the Y Axis Gyroscope Error for 1 rotationErrorCode
configZAxisGyroError(double err)
Configures the Z Axis Gyroscope Error for 1 rotationErrorCode
configZAxisGyroError(double err, int timeoutMs)
Configures the Z Axis Gyroscope Error for 1 rotationvoid
getAllConfigs(Pigeon2Configuration allConfigs)
Gets all persistant settings.void
getAllConfigs(Pigeon2Configuration allConfigs, int timeoutMs)
Gets all persistant settings.ErrorCode
getFaults(Pigeon2_Faults toFill)
Gets the fault statusErrorCode
getGravityVector(double[] gravVector)
Get the Gravity Vector.ErrorCode
getStickyFaults(Pigeon2_Faults toFill)
Gets the sticky fault statusErrorCode
zeroGyroBiasNow()
Performs an offset calibration on gyro biasErrorCode
zeroGyroBiasNow(int timeoutMs)
Performs an offset calibration on gyro biasMethods inherited from class com.ctre.phoenix.sensors.BasePigeon
addYaw, addYaw, clearStickyFaults, clearStickyFaults, configAllSettings, configAllSettings, configFactoryDefault, configFactoryDefault, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, DestroyObject, get6dQuaternion, getAbsoluteCompassHeading, getAccumGyro, getAllConfigs, getAllConfigs, 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
-
Pigeon2
Create a Pigeon object that communicates with Pigeon on CAN Bus.- Parameters:
deviceNumber
- CAN Device Id of Pigeon [0,62]canbus
- Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
-
Pigeon2
Create a Pigeon object that communicates with Pigeon on CAN Bus.- Parameters:
deviceNumber
- CAN Device Id of Pigeon [0,62]
-
-
Method Details
-
configMountPose
Configure the Mount Pose using the primary axis. This is useful if the Pigeon 2.0 is mounted straight, and you only need to describe what axis is forward and what axis is up.- Parameters:
forward
- Axis that points forward from the robotup
- Axis that points up from the robot- Returns:
- OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
-
configMountPose
public ErrorCode configMountPose(Pigeon2.AxisDirection forward, Pigeon2.AxisDirection up, int timeoutMs)Configure the Mount Pose using the primary axis. This is useful if the Pigeon 2.0 is mounted straight, and you only need to describe what axis is forward and what axis is up.- Parameters:
forward
- Axis that points forward from the robotup
- Axis that points up from the robottimeoutMs
- Config timeout in milliseconds.- Returns:
- OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
-
configMountPose
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:
yaw
- Yaw angle needed to reach the current orientation in degrees.pitch
- Pitch angle needed to reach the current orientation in degrees.roll
- Roll angle needed to reach the current orientation in degrees.timeoutMs
- Config timeout in milliseconds.- Returns:
- Worst error code of all config sets.
-
configMountPose
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:
yaw
- Yaw angle needed to reach the current orientation in degrees.pitch
- Pitch angle needed to reach the current orientation in degrees.roll
- Roll angle needed to reach the current orientation in degrees.- Returns:
- Worst error code of all config sets.
-
configMountPoseYaw
Configure the mounting pose Yaw of the Pigeon2. SeeconfigMountPose(double, double, double, int)
- Parameters:
yaw
- Yaw angle needed to reach the current orientation in degrees.timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode of configSet
-
configMountPoseYaw
Configure the mounting pose Yaw of the Pigeon2. SeeconfigMountPose(double, double, double)
- Parameters:
yaw
- Yaw angle needed to reach the current orientation in degrees.- Returns:
- ErrorCode of configSet
-
configMountPosePitch
Configure the mounting pose Pitch of the Pigeon2. SeeconfigMountPose(double, double, double, int)
- Parameters:
pitch
- Pitch angle needed to reach the current orientation in degrees.timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode of configSet
-
configMountPosePitch
Configure the mounting pose Pitch of the Pigeon2. SeeconfigMountPose(double, double, double)
- Parameters:
pitch
- Pitch angle needed to reach the current orientation in degrees.- Returns:
- ErrorCode of configSet
-
configMountPoseRoll
Configure the mounting pose Roll of the Pigeon2. SeeconfigMountPose(double, double, double, int)
- Parameters:
roll
- Roll angle needed to reach the current orientation in degrees.timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode of configSet
-
configMountPoseRoll
Configure the mounting pose Roll of the Pigeon2. SeeconfigMountPose(double, double, double)
- Parameters:
roll
- Roll angle needed to reach the current orientation in degrees.- Returns:
- ErrorCode of configSet
-
configXAxisGyroError
Configures the X Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode fo configSet
-
configXAxisGyroError
Configures the X Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)- Returns:
- ErrorCode fo configSet
-
configYAxisGyroError
Configures the Y Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode fo configSet
-
configYAxisGyroError
Configures the Y Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)- Returns:
- ErrorCode fo configSet
-
configZAxisGyroError
Configures the Z Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode fo configSet
-
configZAxisGyroError
Configures the Z Axis Gyroscope Error for 1 rotation- Parameters:
err
- Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)- Returns:
- ErrorCode fo configSet
-
configEnableCompass
Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use- Parameters:
enable
- Boolean to enable/disable magnetometer fusiontimeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode Status of the config response
-
configEnableCompass
Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use- Parameters:
enable
- Boolean to enable/disable magnetometer fusion- Returns:
- ErrorCode Status of the config response
-
configDisableTemperatureCompensation
Disables temperature compensation from Pigeon2.- Parameters:
disable
- Boolean to disable/enable temperature compensationtimeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode Status of the config response
-
configDisableTemperatureCompensation
Disables temperature compensation from Pigeon2.- Parameters:
disable
- Boolean to disable/enable temperature compensation- Returns:
- ErrorCode Status of the config response
-
configDisableNoMotionCalibration
Disables the no-motion calibration from Pigeon2- Parameters:
disable
- Boolean to disable/enable no-motion calibrationtimeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode Status of the config response
-
configDisableNoMotionCalibration
Disables the no-motion calibration from Pigeon2- Parameters:
disable
- Boolean to disable/enable no-motion calibration- Returns:
- ErrorCode Status of the config response
-
zeroGyroBiasNow
Performs an offset calibration on gyro bias- Parameters:
timeoutMs
- Config timeout in milliseconds.- Returns:
- ErrorCode Status of the config response
-
zeroGyroBiasNow
Performs an offset calibration on gyro bias- Returns:
- ErrorCode Status of the config response
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout 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.
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getGravityVector
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:
gravVector
- Pass in a double array of size 3 to get the gravity vector- Returns:
- Errorcode of getter
-
getFaults
Gets the fault status- Parameters:
toFill
- Container for fault statuses.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getStickyFaults
Gets the sticky fault status- Parameters:
toFill
- Container for sticky fault statuses.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout 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.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settings
-