Class CorePigeon2
- Direct Known Subclasses:
Pigeon2
public class CorePigeon2 extends ParentDevice
// Constants used in Pigeon2 construction final int kPigeon2Id = 0; final String kPigeon2CANbus = "canivore"; // Construct the Pigeon 2 Pigeon2 pigeon = new Pigeon2(kPigeon2Id, kPigeon2CANbus); // Configure the Pigeon2 for basic use Pigeon2Configuration configs = new Pigeon2Configuration(); // This Pigeon is mounted X-up, so we should mount-pose with Pitch at 90 degrees configs.MountPose.MountPoseYaw = 0; configs.MountPose.MountPosePitch = 90; configs.MountPose.MountPoseRoll = 0; // This Pigeon has no need to trim the gyro configs.GyroTrim.GyroScalarX = 0; configs.GyroTrim.GyroScalarY = 0; configs.GyroTrim.GyroScalarZ = 0; // We want the thermal comp and no-motion cal enabled, with the compass disabled for best behavior configs.Pigeon2Features.DisableNoMotionCalibration = false; configs.Pigeon2Features.DisableTemperatureCompensation = false; configs.Pigeon2Features.EnableCompass = false; // Write these configs to the Pigeon2 pigeon.getConfigurator().apply(configs); // Set the yaw to 0 degrees for initial use pigeon.setYaw(0); // Get Yaw Pitch Roll StatusSignals var yaw = pigeon.getYaw(); var pitch = pigeon.getPitch(); var roll = pigeon.getRoll(); // Refresh and print these values System.out.println("Yaw is " + yaw.refresh().toString()); System.out.println("Pitch is " + pitch.refresh().toString()); System.out.println("Roll is " + roll.refresh().toString());
-
Nested Class Summary
Nested classes/interfaces inherited from class com.ctre.phoenix6.hardware.ParentDevice
ParentDevice.MapGenerator<T>
-
Field Summary
-
Constructor Summary
Constructors Constructor Description CorePigeon2(int deviceId)
Constructs a new Pigeon 2 sensor object.CorePigeon2(int deviceId, String canbus)
Constructs a new Pigeon 2 sensor object. -
Method Summary
Modifier and Type Method Description StatusCode
clearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signalStatusCode
clearStickyFault_BootDuringEnable(double timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signalStatusCode
clearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.StatusCode
clearStickyFault_BootIntoMotion(double timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.StatusCode
clearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: AccelerometerStatusCode
clearStickyFault_BootupAccelerometer(double timeoutSeconds)
Clear sticky fault: Bootup checks failed: AccelerometerStatusCode
clearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: GyroscopeStatusCode
clearStickyFault_BootupGyroscope(double timeoutSeconds)
Clear sticky fault: Bootup checks failed: GyroscopeStatusCode
clearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: MagnetometerStatusCode
clearStickyFault_BootupMagnetometer(double timeoutSeconds)
Clear sticky fault: Bootup checks failed: MagnetometerStatusCode
clearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expectedStatusCode
clearStickyFault_DataAcquiredLate(double timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expectedStatusCode
clearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurredStatusCode
clearStickyFault_Hardware(double timeoutSeconds)
Clear sticky fault: Hardware fault occurredStatusCode
clearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.StatusCode
clearStickyFault_LoopTimeSlow(double timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.StatusCode
clearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturatedStatusCode
clearStickyFault_SaturatedAccelerometer(double timeoutSeconds)
Clear sticky fault: Accelerometer values are saturatedStatusCode
clearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturatedStatusCode
clearStickyFault_SaturatedGyroscope(double timeoutSeconds)
Clear sticky fault: Gyroscope values are saturatedStatusCode
clearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturatedStatusCode
clearStickyFault_SaturatedMagnetometer(double timeoutSeconds)
Clear sticky fault: Magnetometer values are saturatedStatusCode
clearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levelsStatusCode
clearStickyFault_Undervoltage(double timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levelsStatusCode
clearStickyFaults()
Clear the sticky faults in the device.StatusCode
clearStickyFaults(double timeoutSeconds)
Clear the sticky faults in the device.StatusSignal<Double>
getAccelerationX()
The acceleration measured by Pigeon2 in the X direction.StatusSignal<Double>
getAccelerationY()
The acceleration measured by Pigeon2 in the Y direction.StatusSignal<Double>
getAccelerationZ()
The acceleration measured by Pigeon2 in the Z direction.StatusSignal<Double>
getAccumGyroX()
The accumulated gyro about the X axis without any sensor fusing.StatusSignal<Double>
getAccumGyroY()
The accumulated gyro about the Y axis without any sensor fusing.StatusSignal<Double>
getAccumGyroZ()
The accumulated gyro about the Z axis without any sensor fusing.StatusSignal<Double>
getAngularVelocityXDevice()
The angular velocity (ω) of the Pigeon 2 about the device's X axis.StatusSignal<Double>
getAngularVelocityXWorld()
Angular Velocity world XStatusSignal<Double>
getAngularVelocityYDevice()
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.StatusSignal<Double>
getAngularVelocityYWorld()
Angular Velocity Quaternion Y ComponentStatusSignal<Double>
getAngularVelocityZDevice()
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.StatusSignal<Double>
getAngularVelocityZWorld()
Angular Velocity Quaternion Z ComponentPigeon2Configurator
getConfigurator()
Gets the configurator to use with this device's configsStatusSignal<Boolean>
getFault_BootDuringEnable()
Device boot while detecting the enable signal Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_BootIntoMotion()
Motion Detected during bootup.StatusSignal<Boolean>
getFault_BootupAccelerometer()
Bootup checks failed: Accelerometer Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_BootupGyroscope()
Bootup checks failed: Gyroscope Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_BootupMagnetometer()
Bootup checks failed: Magnetometer Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_Hardware()
Hardware fault occurred Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_LoopTimeSlow()
Motion stack loop time was slower than expected.StatusSignal<Boolean>
getFault_SaturatedAccelerometer()
Accelerometer values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_SaturatedGyroscope()
Gyroscope values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_SaturatedMagnetometer()
Magnetometer values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_Undervoltage()
Device supply voltage dropped to near brownout levels Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.StatusSignal<Integer>
getFaultField()
Integer representing all faultsStatusSignal<Double>
getGravityVectorX()
The X component of the gravity vector.StatusSignal<Double>
getGravityVectorY()
The Y component of the gravity vector.StatusSignal<Double>
getGravityVectorZ()
The Z component of the gravity vector.StatusSignal<Boolean>
getIsProLicensed()
Whether the device is Phoenix Pro licensed.StatusSignal<Double>
getMagneticFieldX()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.StatusSignal<Double>
getMagneticFieldY()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.StatusSignal<Double>
getMagneticFieldZ()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.StatusSignal<Double>
getNoMotionCount()
The number of times a no-motion event occurred, wraps at 15.StatusSignal<Boolean>
getNoMotionEnabled()
Whether the no-motion calibration feature is enabled.StatusSignal<Double>
getPitch()
Current reported pitch of the Pigeon2.StatusSignal<Double>
getQuatW()
The W component of the reported Quaternion.StatusSignal<Double>
getQuatX()
The X component of the reported Quaternion.StatusSignal<Double>
getQuatY()
The Y component of the reported Quaternion.StatusSignal<Double>
getQuatZ()
The Z component of the reported Quaternion.StatusSignal<Double>
getRawMagneticFieldX()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.StatusSignal<Double>
getRawMagneticFieldY()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.StatusSignal<Double>
getRawMagneticFieldZ()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.StatusSignal<Double>
getRoll()
Current reported roll of the Pigeon2.Pigeon2SimState
getSimState()
Get the simulation state for this device.StatusSignal<Boolean>
getStickyFault_BootDuringEnable()
Device boot while detecting the enable signal Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_BootIntoMotion()
Motion Detected during bootup.StatusSignal<Boolean>
getStickyFault_BootupAccelerometer()
Bootup checks failed: Accelerometer Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_BootupGyroscope()
Bootup checks failed: Gyroscope Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_BootupMagnetometer()
Bootup checks failed: Magnetometer Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_Hardware()
Hardware fault occurred Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_LoopTimeSlow()
Motion stack loop time was slower than expected.StatusSignal<Boolean>
getStickyFault_SaturatedAccelerometer()
Accelerometer values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_SaturatedGyroscope()
Gyroscope values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_SaturatedMagnetometer()
Magnetometer values are saturated Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_Undervoltage()
Device supply voltage dropped to near brownout levels Default Value: False Default Rates: CAN: 4.0 Hz This refreshes and returns a cached StatusSignal object.StatusSignal<Boolean>
getStickyFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.StatusSignal<Integer>
getStickyFaultField()
Integer representing all sticky faultsStatusSignal<Double>
getSupplyVoltage()
Measured supply voltage to the Pigeon2.StatusSignal<Double>
getTemperature()
Temperature of the Pigeon 2.StatusSignal<Boolean>
getTemperatureCompensationDisabled()
Whether the temperature-compensation feature is disabled.StatusSignal<Double>
getUpTime()
How long the Pigeon 2's been up in seconds, caps at 255 seconds.StatusSignal<Integer>
getVersion()
Full Version.StatusSignal<Integer>
getVersionBugfix()
App Bugfix Version number.StatusSignal<Integer>
getVersionBuild()
App Build Version number.StatusSignal<Integer>
getVersionMajor()
App Major Version number.StatusSignal<Integer>
getVersionMinor()
App Minor Version number.StatusSignal<Double>
getYaw()
Current reported yaw of the Pigeon2.StatusCode
setControl(ControlRequest request)
Control motor with generic control request object.StatusCode
setYaw(double newValue)
The yaw to set the Pigeon2 to right now.StatusCode
setYaw(double newValue, double timeoutSeconds)
The yaw to set the Pigeon2 to right now.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
-
CorePigeon2
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.
-
CorePigeon2
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
-
getConfigurator
Gets the configurator to use with this device's configs- Returns:
- Configurator for this object
-
getSimState
Get the simulation state for this device.This function reuses an allocated simulation state object, so it is safe to call this function multiple times in a robot loop.
- Returns:
- Simulation state
-
getVersionMajor
App Major Version number.- Minimum Value: 0
- Maximum Value: 255
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- VersionMajor Status Signal Object
-
getVersionMinor
App Minor Version number.- Minimum Value: 0
- Maximum Value: 255
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- VersionMinor Status Signal Object
-
getVersionBugfix
App Bugfix Version number.- Minimum Value: 0
- Maximum Value: 255
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- VersionBugfix Status Signal Object
-
getVersionBuild
App Build Version number.- Minimum Value: 0
- Maximum Value: 255
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- VersionBuild Status Signal Object
-
getVersion
Full Version. The format is a four byte value.Full Version of firmware in device. The format is a four byte value.
- Minimum Value: 0
- Maximum Value: 4294967295
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- Version Status Signal Object
-
getFaultField
Integer representing all faultsThis returns the fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetFault_*() methods instead.
- Minimum Value: 0
- Maximum Value: 16777215
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- FaultField Status Signal Object
-
getStickyFaultField
Integer representing all sticky faultsThis returns the persistent "sticky" fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetStickyFault_*() methods instead.
- Minimum Value: 0
- Maximum Value: 16777215
- Default Value: 0
- Units:
- CAN: 4.0 Hz
- Returns:
- StickyFaultField Status Signal Object
-
getYaw
Current reported yaw of the Pigeon2.- Minimum Value: -368640.0
- Maximum Value: 368639.99725341797
- Default Value: 0
- Units: deg
- CAN 2.0: 100.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- Yaw Status Signal Object
-
getPitch
Current reported pitch of the Pigeon2.- Minimum Value: -90.0
- Maximum Value: 89.9560546875
- Default Value: 0
- Units: deg
- CAN 2.0: 100.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- Pitch Status Signal Object
-
getRoll
Current reported roll of the Pigeon2.- Minimum Value: -180.0
- Maximum Value: 179.9560546875
- Default Value: 0
- Units: deg
- CAN 2.0: 100.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- Roll Status Signal Object
-
getQuatW
The W component of the reported Quaternion.- Minimum Value: -1.0001220852154804
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 50.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- QuatW Status Signal Object
-
getQuatX
The X component of the reported Quaternion.- Minimum Value: -1.0001220852154804
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 50.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- QuatX Status Signal Object
-
getQuatY
The Y component of the reported Quaternion.- Minimum Value: -1.0001220852154804
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 50.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- QuatY Status Signal Object
-
getQuatZ
The Z component of the reported Quaternion.- Minimum Value: -1.0001220852154804
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 50.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- QuatZ Status Signal Object
-
getGravityVectorX
The X component of the gravity vector.This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.
- Minimum Value: -1.000030518509476
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- GravityVectorX Status Signal Object
-
getGravityVectorY
The Y component of the gravity vector.This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.
- Minimum Value: -1.000030518509476
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- GravityVectorY Status Signal Object
-
getGravityVectorZ
The Z component of the gravity vector.This is the Z component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.
- Minimum Value: -1.000030518509476
- Maximum Value: 1.0
- Default Value: 0
- Units:
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- GravityVectorZ Status Signal Object
-
getTemperature
Temperature of the Pigeon 2.- Minimum Value: -128.0
- Maximum Value: 127.99609375
- Default Value: 0
- Units: ℃
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- Temperature Status Signal Object
-
getNoMotionEnabled
Whether the no-motion calibration feature is enabled.- Default Value: 0
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- NoMotionEnabled Status Signal Object
-
getNoMotionCount
The number of times a no-motion event occurred, wraps at 15.- Minimum Value: 0
- Maximum Value: 15
- Default Value: 0
- Units:
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- NoMotionCount Status Signal Object
-
getTemperatureCompensationDisabled
Whether the temperature-compensation feature is disabled.- Default Value: 0
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- TemperatureCompensationDisabled Status Signal Object
-
getUpTime
How long the Pigeon 2's been up in seconds, caps at 255 seconds.- Minimum Value: 0
- Maximum Value: 255
- Default Value: 0
- Units: s
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- UpTime Status Signal Object
-
getAccumGyroX
The accumulated gyro about the X axis without any sensor fusing.- Minimum Value: -23040.0
- Maximum Value: 23039.9560546875
- Default Value: 0
- Units: deg
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccumGyroX Status Signal Object
-
getAccumGyroY
The accumulated gyro about the Y axis without any sensor fusing.- Minimum Value: -23040.0
- Maximum Value: 23039.9560546875
- Default Value: 0
- Units: deg
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccumGyroY Status Signal Object
-
getAccumGyroZ
The accumulated gyro about the Z axis without any sensor fusing.- Minimum Value: -23040.0
- Maximum Value: 23039.9560546875
- Default Value: 0
- Units: deg
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccumGyroZ Status Signal Object
-
getAngularVelocityXWorld
Angular Velocity world XThis is the X component of the angular velocity with respect to the world frame and is mount-calibrated.
- Minimum Value: -2048.0
- Maximum Value: 2047.99609375
- Default Value: 0
- Units: dps
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AngularVelocityXWorld Status Signal Object
-
getAngularVelocityYWorld
Angular Velocity Quaternion Y ComponentThis is the Y component of the angular velocity with respect to the world frame and is mount-calibrated.
- Minimum Value: -2048.0
- Maximum Value: 2047.99609375
- Default Value: 0
- Units: dps
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AngularVelocityYWorld Status Signal Object
-
getAngularVelocityZWorld
Angular Velocity Quaternion Z ComponentThis is the Z component of the angular velocity with respect to the world frame and is mount-calibrated.
- Minimum Value: -2048.0
- Maximum Value: 2047.99609375
- Default Value: 0
- Units: dps
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AngularVelocityZWorld Status Signal Object
-
getAccelerationX
The acceleration measured by Pigeon2 in the X direction.This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.
- Minimum Value: -2.0
- Maximum Value: 1.99993896484375
- Default Value: 0
- Units: g
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccelerationX Status Signal Object
-
getAccelerationY
The acceleration measured by Pigeon2 in the Y direction.This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.
- Minimum Value: -2.0
- Maximum Value: 1.99993896484375
- Default Value: 0
- Units: g
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccelerationY Status Signal Object
-
getAccelerationZ
The acceleration measured by Pigeon2 in the Z direction.This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.
- Minimum Value: -2.0
- Maximum Value: 1.99993896484375
- Default Value: 0
- Units: g
- CAN 2.0: 10.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- AccelerationZ Status Signal Object
-
getSupplyVoltage
Measured supply voltage to the Pigeon2.- Minimum Value: 0.0
- Maximum Value: 31.99951171875
- Default Value: 0
- Units: V
- CAN 2.0: 4.0 Hz
- CAN FD: 100.0 Hz (TimeSynced with Pro)
- Returns:
- SupplyVoltage Status Signal Object
-
getAngularVelocityXDevice
The angular velocity (ω) of the Pigeon 2 about the device's X axis.This value is not mount-calibrated
- Minimum Value: -1998.048780487805
- Maximum Value: 1997.987804878049
- Default Value: 0
- Units: dps
- CAN: 4.0 Hz
- Returns:
- AngularVelocityXDevice Status Signal Object
-
getAngularVelocityYDevice
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.This value is not mount-calibrated
- Minimum Value: -1998.048780487805
- Maximum Value: 1997.987804878049
- Default Value: 0
- Units: dps
- CAN: 4.0 Hz
- Returns:
- AngularVelocityYDevice Status Signal Object
-
getAngularVelocityZDevice
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.This value is not mount-calibrated
- Minimum Value: -1998.048780487805
- Maximum Value: 1997.987804878049
- Default Value: 0
- Units: dps
- CAN: 4.0 Hz
- Returns:
- AngularVelocityZDevice Status Signal Object
-
getMagneticFieldX
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- MagneticFieldX Status Signal Object
-
getMagneticFieldY
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- MagneticFieldY Status Signal Object
-
getMagneticFieldZ
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- MagneticFieldZ Status Signal Object
-
getRawMagneticFieldX
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- RawMagneticFieldX Status Signal Object
-
getRawMagneticFieldY
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- RawMagneticFieldY Status Signal Object
-
getRawMagneticFieldZ
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. This is only valid after performing a magnetometer calibration.- Minimum Value: -19660.8
- Maximum Value: 19660.2
- Default Value: 0
- Units: uT
- CAN: 4.0 Hz
- Returns:
- RawMagneticFieldZ Status Signal Object
-
getIsProLicensed
Whether the device is Phoenix Pro licensed.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- IsProLicensed Status Signal Object
-
getFault_Hardware
Hardware fault occurred- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_Hardware Status Signal Object
-
getStickyFault_Hardware
Hardware fault occurred- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_Hardware Status Signal Object
-
getFault_Undervoltage
Device supply voltage dropped to near brownout levels- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_Undervoltage Status Signal Object
-
getStickyFault_Undervoltage
Device supply voltage dropped to near brownout levels- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_Undervoltage Status Signal Object
-
getFault_BootDuringEnable
Device boot while detecting the enable signal- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_BootDuringEnable Status Signal Object
-
getStickyFault_BootDuringEnable
Device boot while detecting the enable signal- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_BootDuringEnable Status Signal Object
-
getFault_UnlicensedFeatureInUse
An unlicensed feature is in use, device may not behave as expected.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_UnlicensedFeatureInUse Status Signal Object
-
getStickyFault_UnlicensedFeatureInUse
An unlicensed feature is in use, device may not behave as expected.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_UnlicensedFeatureInUse Status Signal Object
-
getFault_BootupAccelerometer
Bootup checks failed: Accelerometer- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_BootupAccelerometer Status Signal Object
-
getStickyFault_BootupAccelerometer
Bootup checks failed: Accelerometer- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_BootupAccelerometer Status Signal Object
-
getFault_BootupGyroscope
Bootup checks failed: Gyroscope- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_BootupGyroscope Status Signal Object
-
getStickyFault_BootupGyroscope
Bootup checks failed: Gyroscope- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_BootupGyroscope Status Signal Object
-
getFault_BootupMagnetometer
Bootup checks failed: Magnetometer- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_BootupMagnetometer Status Signal Object
-
getStickyFault_BootupMagnetometer
Bootup checks failed: Magnetometer- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_BootupMagnetometer Status Signal Object
-
getFault_BootIntoMotion
Motion Detected during bootup.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_BootIntoMotion Status Signal Object
-
getStickyFault_BootIntoMotion
Motion Detected during bootup.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_BootIntoMotion Status Signal Object
-
getFault_DataAcquiredLate
Motion stack data acquisition was slower than expected- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_DataAcquiredLate Status Signal Object
-
getStickyFault_DataAcquiredLate
Motion stack data acquisition was slower than expected- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_DataAcquiredLate Status Signal Object
-
getFault_LoopTimeSlow
Motion stack loop time was slower than expected.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_LoopTimeSlow Status Signal Object
-
getStickyFault_LoopTimeSlow
Motion stack loop time was slower than expected.- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_LoopTimeSlow Status Signal Object
-
getFault_SaturatedMagnetometer
Magnetometer values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_SaturatedMagnetometer Status Signal Object
-
getStickyFault_SaturatedMagnetometer
Magnetometer values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_SaturatedMagnetometer Status Signal Object
-
getFault_SaturatedAccelerometer
Accelerometer values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_SaturatedAccelerometer Status Signal Object
-
getStickyFault_SaturatedAccelerometer
Accelerometer values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_SaturatedAccelerometer Status Signal Object
-
getFault_SaturatedGyroscope
Gyroscope values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- Fault_SaturatedGyroscope Status Signal Object
-
getStickyFault_SaturatedGyroscope
Gyroscope values are saturated- Default Value: False
- CAN: 4.0 Hz
- Returns:
- StickyFault_SaturatedGyroscope Status Signal Object
-
setControl
Control motor with generic control request object.User must make sure the specified object is castable to a valid control request, otherwise this function will fail at run-time and return the NotSupported StatusCode
- Parameters:
request
- Control object to request of the device- Returns:
- Status Code of the request, 0 is OK
-
setYaw
The yaw to set the Pigeon2 to right now.- Parameters:
newValue
- Value to set to. Units are in deg.timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
setYaw
The yaw to set the Pigeon2 to right now.This will wait up to 0.050 seconds (50ms) by default.
- Parameters:
newValue
- Value to set to. Units are in deg.- Returns:
- StatusCode of the set command
-
clearStickyFaults
Clear the sticky faults in the device.This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.
- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFaults
Clear the sticky faults in the device.This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.
This will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_Hardware
Clear sticky fault: Hardware fault occurred- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_Hardware
Clear sticky fault: Hardware fault occurredThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_Undervoltage
Clear sticky fault: Device supply voltage dropped to near brownout levels- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_Undervoltage
Clear sticky fault: Device supply voltage dropped to near brownout levelsThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_BootDuringEnable
Clear sticky fault: Device boot while detecting the enable signal- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_BootDuringEnable
Clear sticky fault: Device boot while detecting the enable signalThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupAccelerometer
Clear sticky fault: Bootup checks failed: Accelerometer- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupAccelerometer
Clear sticky fault: Bootup checks failed: AccelerometerThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupGyroscope
Clear sticky fault: Bootup checks failed: Gyroscope- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupGyroscope
Clear sticky fault: Bootup checks failed: GyroscopeThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupMagnetometer
Clear sticky fault: Bootup checks failed: Magnetometer- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_BootupMagnetometer
Clear sticky fault: Bootup checks failed: MagnetometerThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_BootIntoMotion
Clear sticky fault: Motion Detected during bootup.- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_BootIntoMotion
Clear sticky fault: Motion Detected during bootup.This will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_DataAcquiredLate
Clear sticky fault: Motion stack data acquisition was slower than expected- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_DataAcquiredLate
Clear sticky fault: Motion stack data acquisition was slower than expectedThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_LoopTimeSlow
Clear sticky fault: Motion stack loop time was slower than expected.- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_LoopTimeSlow
Clear sticky fault: Motion stack loop time was slower than expected.This will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedMagnetometer
Clear sticky fault: Magnetometer values are saturated- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedMagnetometer
Clear sticky fault: Magnetometer values are saturatedThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedAccelerometer
Clear sticky fault: Accelerometer values are saturated- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedAccelerometer
Clear sticky fault: Accelerometer values are saturatedThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedGyroscope
Clear sticky fault: Gyroscope values are saturated- Parameters:
timeoutSeconds
- Maximum time to wait up to in seconds.- Returns:
- StatusCode of the set command
-
clearStickyFault_SaturatedGyroscope
Clear sticky fault: Gyroscope values are saturatedThis will wait up to 0.050 seconds (50ms) by default.
- Returns:
- StatusCode of the set command
-