Class Pigeon2
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class Pigeon2 extends CorePigeon2 implements Sendable, AutoCloseable
-
Nested Class Summary
Nested classes/interfaces inherited from class com.ctre.phoenix6.hardware.ParentDevice
ParentDevice.MapGenerator<T>
-
Field Summary
-
Constructor Summary
-
Method Summary
Modifier and Type Method Description void
close()
double
getAngle()
Returns the heading of the robot in degrees.double
getRate()
Returns the rate of rotation of the Pigeon 2.Rotation2d
getRotation2d()
Returns the heading of the robot as aRotation2d
.Rotation3d
getRotation3d()
Returns the orientation of the robot as aRotation3d
created from the quaternion signals.void
initSendable(SendableBuilder builder)
void
reset()
Resets the Pigeon 2 to a heading of zero.Methods inherited from class com.ctre.phoenix6.hardware.core.CorePigeon2
clearStickyFault_BootDuringEnable, clearStickyFault_BootDuringEnable, clearStickyFault_BootIntoMotion, clearStickyFault_BootIntoMotion, clearStickyFault_BootupAccelerometer, clearStickyFault_BootupAccelerometer, clearStickyFault_BootupGyroscope, clearStickyFault_BootupGyroscope, clearStickyFault_BootupMagnetometer, clearStickyFault_BootupMagnetometer, clearStickyFault_DataAcquiredLate, clearStickyFault_DataAcquiredLate, clearStickyFault_Hardware, clearStickyFault_Hardware, clearStickyFault_LoopTimeSlow, clearStickyFault_LoopTimeSlow, clearStickyFault_SaturatedAccelerometer, clearStickyFault_SaturatedAccelerometer, clearStickyFault_SaturatedGyroscope, clearStickyFault_SaturatedGyroscope, clearStickyFault_SaturatedMagnetometer, clearStickyFault_SaturatedMagnetometer, clearStickyFault_Undervoltage, clearStickyFault_Undervoltage, clearStickyFaults, clearStickyFaults, getAccelerationX, getAccelerationY, getAccelerationZ, getAccumGyroX, getAccumGyroY, getAccumGyroZ, getAngularVelocityXDevice, getAngularVelocityXWorld, getAngularVelocityYDevice, getAngularVelocityYWorld, getAngularVelocityZDevice, getAngularVelocityZWorld, getConfigurator, getFault_BootDuringEnable, getFault_BootIntoMotion, getFault_BootupAccelerometer, getFault_BootupGyroscope, getFault_BootupMagnetometer, getFault_DataAcquiredLate, getFault_Hardware, getFault_LoopTimeSlow, getFault_SaturatedAccelerometer, getFault_SaturatedGyroscope, getFault_SaturatedMagnetometer, getFault_Undervoltage, getFault_UnlicensedFeatureInUse, getFaultField, getGravityVectorX, getGravityVectorY, getGravityVectorZ, getIsProLicensed, getMagneticFieldX, getMagneticFieldY, getMagneticFieldZ, getNoMotionCount, getNoMotionEnabled, getPitch, getQuatW, getQuatX, getQuatY, getQuatZ, getRawMagneticFieldX, getRawMagneticFieldY, getRawMagneticFieldZ, getRoll, getSimState, getStickyFault_BootDuringEnable, getStickyFault_BootIntoMotion, getStickyFault_BootupAccelerometer, getStickyFault_BootupGyroscope, getStickyFault_BootupMagnetometer, getStickyFault_DataAcquiredLate, getStickyFault_Hardware, getStickyFault_LoopTimeSlow, getStickyFault_SaturatedAccelerometer, getStickyFault_SaturatedGyroscope, getStickyFault_SaturatedMagnetometer, getStickyFault_Undervoltage, getStickyFault_UnlicensedFeatureInUse, getStickyFaultField, getSupplyVoltage, getTemperature, getTemperatureCompensationDisabled, getUpTime, getVersion, getVersionBugfix, getVersionBuild, getVersionMajor, getVersionMinor, getYaw, setControl, setYaw, setYaw
Methods inherited from class com.ctre.phoenix6.hardware.ParentDevice
getAppliedControl, getDeviceHash, getDeviceID, getNetwork, getResetOccurredChecker, hasResetOccurred, lookupStatusSignal, lookupStatusSignal, optimizeBusUtilization, optimizeBusUtilization, optimizeBusUtilization, optimizeBusUtilizationForAll, optimizeBusUtilizationForAll, setControlPrivate
-
Constructor Details
-
Pigeon2
Constructs a new Pigeon 2 sensor object.Constructs the device using the default CAN bus for the system:
- "rio" on roboRIO
- "can0" on Linux
- "*" on Windows
- Parameters:
deviceId
- ID of the device, as configured in Phoenix Tuner.
-
Pigeon2
Constructs a new Pigeon 2 sensor object.- Parameters:
deviceId
- ID of the device, as configured in Phoenix Tuner.canbus
- Name of the CAN bus this device is on. Possible CAN bus strings are:- "rio" for the native roboRIO CAN bus
- CANivore name or serial number
- SocketCAN interface (non-FRC Linux only)
- "*" for any CANivore seen by the program
- empty string (default) to select the default for the
system:
- "rio" on roboRIO
- "can0" on Linux
- "*" on Windows
-
-
Method Details
-
close
- Specified by:
close
in interfaceAutoCloseable
-
reset
Resets the Pigeon 2 to a heading of zero.This can be used if there is significant drift in the gyro, and it needs to be recalibrated after it has been running.
-
getAngle
Returns the heading of the robot in degrees.The angle increases as the Pigeon 2 turns clockwise when looked at from the top. This follows the NED axis convention.
The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
- Returns:
- The current heading of the robot in degrees
-
getRate
Returns the rate of rotation of the Pigeon 2.The rate is positive as the Pigeon 2 turns clockwise when looked at from the top.
- Returns:
- The current rate in degrees per second
-
getRotation2d
Returns the heading of the robot as aRotation2d
.The angle increases as the Pigeon 2 turns counterclockwise when looked at from the top. This follows the NWU axis convention.
The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
- Returns:
- The current heading of the robot as a
Rotation2d
-
getRotation3d
Returns the orientation of the robot as aRotation3d
created from the quaternion signals.- Returns:
- The current orientation of the robot as a
Rotation3d
-
initSendable
- Specified by:
initSendable
in interfaceSendable
-