Class CorePigeon2
Class description for the Pigeon 2 IMU sensor that measures orientation.
public class CorePigeon2 : ParentDevice, CommonDevice
- Inheritance
-
CorePigeon2
- Implements
- Derived
- Inherited Members
Constructors
CorePigeon2(int)
Constructs a new Pigeon 2 sensor object.
Constructs the device using the default CAN bus for the system (see CANBus(string)).public CorePigeon2(int deviceId)
Parameters
deviceIdintID of the device, as configured in Phoenix Tuner
CorePigeon2(int, CANBus)
Constructs a new Pigeon 2 sensor object.
public CorePigeon2(int deviceId, CANBus canbus)
Parameters
deviceIdintID of the device, as configured in Phoenix Tuner
canbusCANBusThe CAN bus this device is on
CorePigeon2(int, string)
Constructs a new Pigeon 2 sensor object.
[Obsolete("Constructing devices with a CAN bus string is deprecated for removal in the 2027 season. Construct devices using a CANBus instance instead.")]
public CorePigeon2(int deviceId, string canbus)
Parameters
deviceIdintID of the device, as configured in Phoenix Tuner
canbusstringName of the CAN bus. Possible CAN bus strings are:
- 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:
- "can0" on Linux
- "" on Windows
Properties
Configurator
The configurator for this device. Users may use this to refresh and apply configs, such as the Pigeon2Configuration object
public Pigeon2Configurator Configurator { get; }
Property Value
SimState
Gets 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.public Pigeon2SimState SimState { get; }
Property Value
Methods
ClearStickyFault_BootDuringEnable(double)
Clear sticky fault: Device boot while detecting the enable signal
public StatusCode ClearStickyFault_BootDuringEnable(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_BootIntoMotion(double)
Clear sticky fault: Motion Detected during bootup.
public StatusCode ClearStickyFault_BootIntoMotion(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_BootupAccelerometer(double)
Clear sticky fault: Bootup checks failed: Accelerometer
public StatusCode ClearStickyFault_BootupAccelerometer(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_BootupGyroscope(double)
Clear sticky fault: Bootup checks failed: Gyroscope
public StatusCode ClearStickyFault_BootupGyroscope(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_BootupMagnetometer(double)
Clear sticky fault: Bootup checks failed: Magnetometer
public StatusCode ClearStickyFault_BootupMagnetometer(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_DataAcquiredLate(double)
Clear sticky fault: Motion stack data acquisition was slower than expected
public StatusCode ClearStickyFault_DataAcquiredLate(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_Hardware(double)
Clear sticky fault: Hardware fault occurred
public StatusCode ClearStickyFault_Hardware(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_LoopTimeSlow(double)
Clear sticky fault: Motion stack loop time was slower than expected.
public StatusCode ClearStickyFault_LoopTimeSlow(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_SaturatedAccelerometer(double)
Clear sticky fault: Accelerometer values are saturated
public StatusCode ClearStickyFault_SaturatedAccelerometer(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_SaturatedGyroscope(double)
Clear sticky fault: Gyroscope values are saturated
public StatusCode ClearStickyFault_SaturatedGyroscope(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_SaturatedMagnetometer(double)
Clear sticky fault: Magnetometer values are saturated
public StatusCode ClearStickyFault_SaturatedMagnetometer(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_Undervoltage(double)
Clear sticky fault: Device supply voltage dropped to near brownout levels
public StatusCode ClearStickyFault_Undervoltage(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFault_UnlicensedFeatureInUse(double)
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
public StatusCode ClearStickyFault_UnlicensedFeatureInUse(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
ClearStickyFaults(double)
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.public StatusCode ClearStickyFaults(double timeoutSeconds = 0.1)
Parameters
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command
GetAccelerationX(bool)
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 Value1.99993896484375
- Default Value0
- Unitsg
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccelerationX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccelerationX Status Signal Object
GetAccelerationY(bool)
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 Value1.99993896484375
- Default Value0
- Unitsg
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccelerationY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccelerationY Status Signal Object
GetAccelerationZ(bool)
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 Value1.99993896484375
- Default Value0
- Unitsg
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccelerationZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccelerationZ Status Signal Object
GetAccumGyroX(bool)
The accumulated gyro about the X axis without any sensor fusing.
- Minimum Value-23040.0
- Maximum Value23039.9560546875
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccumGyroX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccumGyroX Status Signal Object
GetAccumGyroY(bool)
The accumulated gyro about the Y axis without any sensor fusing.
- Minimum Value-23040.0
- Maximum Value23039.9560546875
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccumGyroY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccumGyroY Status Signal Object
GetAccumGyroZ(bool)
The accumulated gyro about the Z axis without any sensor fusing.
- Minimum Value-23040.0
- Maximum Value23039.9560546875
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAccumGyroZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AccumGyroZ Status Signal Object
GetAngularVelocityXDevice(bool)
The angular velocity (ω) of the Pigeon 2 about the device's X axis.
This value is not mount-calibrated.- Minimum Value-1998.048780487805
- Maximum Value1997.987804878049
- Default Value0
- Unitsdps
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetAngularVelocityXDevice(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityXDevice Status Signal Object
GetAngularVelocityXWorld(bool)
The angular velocity (ω) of the Pigeon 2 about the X axis with respect to the world frame. This value is mount-calibrated.
- Minimum Value-2048.0
- Maximum Value2047.99609375
- Default Value0
- Unitsdps
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAngularVelocityXWorld(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityXWorld Status Signal Object
GetAngularVelocityYDevice(bool)
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
This value is not mount-calibrated.- Minimum Value-1998.048780487805
- Maximum Value1997.987804878049
- Default Value0
- Unitsdps
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetAngularVelocityYDevice(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityYDevice Status Signal Object
GetAngularVelocityYWorld(bool)
The angular velocity (ω) of the Pigeon 2 about the Y axis with respect to the world frame. This value is mount-calibrated.
- Minimum Value-2048.0
- Maximum Value2047.99609375
- Default Value0
- Unitsdps
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAngularVelocityYWorld(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityYWorld Status Signal Object
GetAngularVelocityZDevice(bool)
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
This value is not mount-calibrated.- Minimum Value-1998.048780487805
- Maximum Value1997.987804878049
- Default Value0
- Unitsdps
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetAngularVelocityZDevice(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityZDevice Status Signal Object
GetAngularVelocityZWorld(bool)
The angular velocity (ω) of the Pigeon 2 about the Z axis with respect to the world frame. This value is mount-calibrated.
- Minimum Value-2048.0
- Maximum Value2047.99609375
- Default Value0
- Unitsdps
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetAngularVelocityZWorld(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
AngularVelocityZWorld Status Signal Object
GetFaultField(bool)
Integer representing all 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 Value0
- Maximum Value4294967295
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetFaultField(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
FaultField Status Signal Object
GetFault_BootDuringEnable(bool)
Device boot while detecting the enable signal
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_BootDuringEnable(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_BootDuringEnable Status Signal Object
GetFault_BootIntoMotion(bool)
Motion Detected during bootup.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_BootIntoMotion(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_BootIntoMotion Status Signal Object
GetFault_BootupAccelerometer(bool)
Bootup checks failed: Accelerometer
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_BootupAccelerometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_BootupAccelerometer Status Signal Object
GetFault_BootupGyroscope(bool)
Bootup checks failed: Gyroscope
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_BootupGyroscope(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_BootupGyroscope Status Signal Object
GetFault_BootupMagnetometer(bool)
Bootup checks failed: Magnetometer
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_BootupMagnetometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_BootupMagnetometer Status Signal Object
GetFault_DataAcquiredLate(bool)
Motion stack data acquisition was slower than expected
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_DataAcquiredLate(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_DataAcquiredLate Status Signal Object
GetFault_Hardware(bool)
Hardware fault occurred
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_Hardware(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_Hardware Status Signal Object
GetFault_LoopTimeSlow(bool)
Motion stack loop time was slower than expected.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_LoopTimeSlow(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_LoopTimeSlow Status Signal Object
GetFault_SaturatedAccelerometer(bool)
Accelerometer values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_SaturatedAccelerometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_SaturatedAccelerometer Status Signal Object
GetFault_SaturatedGyroscope(bool)
Gyroscope values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_SaturatedGyroscope(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_SaturatedGyroscope Status Signal Object
GetFault_SaturatedMagnetometer(bool)
Magnetometer values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_SaturatedMagnetometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_SaturatedMagnetometer Status Signal Object
GetFault_Undervoltage(bool)
Device supply voltage dropped to near brownout levels
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_Undervoltage(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_Undervoltage Status Signal Object
GetFault_UnlicensedFeatureInUse(bool)
An unlicensed feature is in use, device may not behave as expected.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetFault_UnlicensedFeatureInUse(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
Fault_UnlicensedFeatureInUse Status Signal Object
GetGravityVectorX(bool)
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 Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetGravityVectorX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
GravityVectorX Status Signal Object
GetGravityVectorY(bool)
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 Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetGravityVectorY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
GravityVectorY Status Signal Object
GetGravityVectorZ(bool)
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 Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.010.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetGravityVectorZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
GravityVectorZ Status Signal Object
GetIsProLicensed(bool)
Whether the device is Phoenix Pro licensed.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetIsProLicensed(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
IsProLicensed Status Signal Object
GetMagneticFieldX(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetMagneticFieldX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
MagneticFieldX Status Signal Object
GetMagneticFieldY(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetMagneticFieldY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
MagneticFieldY Status Signal Object
GetMagneticFieldZ(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetMagneticFieldZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
MagneticFieldZ Status Signal Object
GetNoMotionCount(bool)
The number of times a no-motion event occurred, wraps at 15.
- Minimum Value0
- Maximum Value15
- Default Value0
- Units
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetNoMotionCount(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
NoMotionCount Status Signal Object
GetNoMotionEnabled(bool)
Whether the no-motion calibration feature is enabled.
- Default Value0
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<bool> GetNoMotionEnabled(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
NoMotionEnabled Status Signal Object
GetPitch(bool)
Current reported pitch of the Pigeon2.
- Minimum Value-90.0
- Maximum Value89.9560546875
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.0100.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetPitch(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
Pitch Status Signal Object
GetQuatW(bool)
The W component of the reported Quaternion.
- Minimum Value-1.0001220852154804
- Maximum Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.050.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetQuatW(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
QuatW Status Signal Object
GetQuatX(bool)
The X component of the reported Quaternion.
- Minimum Value-1.0001220852154804
- Maximum Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.050.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetQuatX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
QuatX Status Signal Object
GetQuatY(bool)
The Y component of the reported Quaternion.
- Minimum Value-1.0001220852154804
- Maximum Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.050.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetQuatY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
QuatY Status Signal Object
GetQuatZ(bool)
The Z component of the reported Quaternion.
- Minimum Value-1.0001220852154804
- Maximum Value1.0
- Default Value0
- Units
Default Rates:
- CAN 2.050.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetQuatZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
QuatZ Status Signal Object
GetRawMagneticFieldX(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetRawMagneticFieldX(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
RawMagneticFieldX Status Signal Object
GetRawMagneticFieldY(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetRawMagneticFieldY(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
RawMagneticFieldY Status Signal Object
GetRawMagneticFieldZ(bool)
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 Value19660.2
- Default Value0
- UnitsuT
Default Rates:
- CAN4.0 Hz
public StatusSignal<double> GetRawMagneticFieldZ(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
RawMagneticFieldZ Status Signal Object
GetRoll(bool)
Current reported roll of the Pigeon2.
- Minimum Value-180.0
- Maximum Value179.9560546875
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.0100.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetRoll(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
Roll Status Signal Object
GetStickyFaultField(bool)
Integer representing all (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 Value0
- Maximum Value4294967295
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetStickyFaultField(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
StickyFaultField Status Signal Object
GetStickyFault_BootDuringEnable(bool)
Device boot while detecting the enable signal
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_BootDuringEnable(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_BootDuringEnable Status Signal Object
GetStickyFault_BootIntoMotion(bool)
Motion Detected during bootup.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_BootIntoMotion(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_BootIntoMotion Status Signal Object
GetStickyFault_BootupAccelerometer(bool)
Bootup checks failed: Accelerometer
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_BootupAccelerometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_BootupAccelerometer Status Signal Object
GetStickyFault_BootupGyroscope(bool)
Bootup checks failed: Gyroscope
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_BootupGyroscope(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_BootupGyroscope Status Signal Object
GetStickyFault_BootupMagnetometer(bool)
Bootup checks failed: Magnetometer
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_BootupMagnetometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_BootupMagnetometer Status Signal Object
GetStickyFault_DataAcquiredLate(bool)
Motion stack data acquisition was slower than expected
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_DataAcquiredLate(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_DataAcquiredLate Status Signal Object
GetStickyFault_Hardware(bool)
Hardware fault occurred
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_Hardware(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_Hardware Status Signal Object
GetStickyFault_LoopTimeSlow(bool)
Motion stack loop time was slower than expected.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_LoopTimeSlow(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_LoopTimeSlow Status Signal Object
GetStickyFault_SaturatedAccelerometer(bool)
Accelerometer values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_SaturatedAccelerometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_SaturatedAccelerometer Status Signal Object
GetStickyFault_SaturatedGyroscope(bool)
Gyroscope values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_SaturatedGyroscope(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_SaturatedGyroscope Status Signal Object
GetStickyFault_SaturatedMagnetometer(bool)
Magnetometer values are saturated
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_SaturatedMagnetometer(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_SaturatedMagnetometer Status Signal Object
GetStickyFault_Undervoltage(bool)
Device supply voltage dropped to near brownout levels
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_Undervoltage(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_Undervoltage Status Signal Object
GetStickyFault_UnlicensedFeatureInUse(bool)
An unlicensed feature is in use, device may not behave as expected.
- Default ValueFalse
Default Rates:
- CAN4.0 Hz
public StatusSignal<bool> GetStickyFault_UnlicensedFeatureInUse(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
StickyFault_UnlicensedFeatureInUse Status Signal Object
GetSupplyVoltage(bool)
Measured supply voltage to the Pigeon2.
- Minimum Value0.0
- Maximum Value31.99951171875
- Default Value0
- UnitsV
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetSupplyVoltage(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
SupplyVoltage Status Signal Object
GetTemperature(bool)
Temperature of the Pigeon 2.
- Minimum Value-128.0
- Maximum Value127.99609375
- Default Value0
- Units℃
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetTemperature(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
Temperature Status Signal Object
GetTemperatureCompensationDisabled(bool)
Whether the temperature-compensation feature is disabled.
- Default Value0
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<bool> GetTemperatureCompensationDisabled(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<bool>
TemperatureCompensationDisabled Status Signal Object
GetUpTime(bool)
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
- Minimum Value0
- Maximum Value255
- Default Value0
- Unitss
Default Rates:
- CAN 2.04.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetUpTime(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
UpTime Status Signal Object
GetVersion(bool)
Full Version of firmware in device. The format is a four byte value.
- Minimum Value0
- Maximum Value4294967295
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetVersion(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
Version Status Signal Object
GetVersionBugfix(bool)
App Bugfix Version number.
- Minimum Value0
- Maximum Value255
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetVersionBugfix(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
VersionBugfix Status Signal Object
GetVersionBuild(bool)
App Build Version number.
- Minimum Value0
- Maximum Value255
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetVersionBuild(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
VersionBuild Status Signal Object
GetVersionMajor(bool)
App Major Version number.
- Minimum Value0
- Maximum Value255
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetVersionMajor(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
VersionMajor Status Signal Object
GetVersionMinor(bool)
App Minor Version number.
- Minimum Value0
- Maximum Value255
- Default Value0
- Units
Default Rates:
- CAN4.0 Hz
public StatusSignal<int> GetVersionMinor(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<int>
VersionMinor Status Signal Object
GetYaw(bool)
Current reported yaw of the Pigeon2.
- Minimum Value-368640.0
- Maximum Value368639.99725341797
- Default Value0
- Unitsdeg
Default Rates:
- CAN 2.0100.0 Hz
- CAN FD100.0 Hz (TimeSynced with Pro)
public StatusSignal<double> GetYaw(bool refresh = true)
Parameters
refreshboolWhether to refresh the StatusSignal before returning it; defaults to true
Returns
- StatusSignal<double>
Yaw Status Signal Object
SetControl(ControlRequest)
Control device 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 StatusCodepublic StatusCode SetControl(ControlRequest request)
Parameters
requestControlRequestControl object to request of the device
Returns
- StatusCode
Status Code of the request, 0 is OK
SetYaw(double, double)
The yaw to set the Pigeon2 to right now.
public StatusCode SetYaw(double newValue, double timeoutSeconds = 0.1)
Parameters
newValuedoubleValue to set to. Units are in deg.
timeoutSecondsdoubleMaximum time to wait up to in seconds.
Returns
- StatusCode
StatusCode of the set command