|
| 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) |
|
| 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 () |
|
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
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
-
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.
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
-
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.