Class CorePigeon2

Direct Known Subclasses:
Pigeon2

public class CorePigeon2
extends ParentDevice
Class description for the Pigeon 2 IMU sensor that measures orientation.
  • Constructor Details

    • CorePigeon2

      public CorePigeon2​(int deviceId)
      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

      public CorePigeon2​(int deviceId, String canbus)
      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

    • reportIfTooOld

      protected void reportIfTooOld()
      Specified by:
      reportIfTooOld in class ParentDevice
    • hasResetOccurred

      public boolean hasResetOccurred()
      Returns:
      true if device has reset since the previous call of this routine.
    • 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:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionMajor Status Signal Value object
    • getVersionMinor

      App Minor Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionMinor Status Signal Value object
    • getVersionBugfix

      App Bugfix Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionBugfix Status Signal Value object
    • getVersionBuild

      App Build Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionBuild Status Signal Value 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:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Version Status Signal Value object
    • getFaultField

      Integer representing all faults

      This 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: 1048575
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      FaultField Status Signal Value object
    • getStickyFaultField

      Integer representing all sticky faults

      This 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: 1048575
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFaultField Status Signal Value object
    • getYaw

      Current reported yaw of the Pigeon2.
      • Minimum Value: -368640.0
      • Maximum Value: 368639.99725341797
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      Yaw Status Signal Value object
    • getPitch

      Current reported pitch of the Pigeon2.
      • Minimum Value: -90.0
      • Maximum Value: 89.9560546875
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      Pitch Status Signal Value object
    • getRoll

      Current reported roll of the Pigeon2.
      • Minimum Value: -180.0
      • Maximum Value: 179.9560546875
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      Roll Status Signal Value object
    • getQuatW

      The W component of the reported Quaternion.
      • Minimum Value: -1.0001220852154804
      • Maximum Value: 1.0
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      QuatW Status Signal Value object
    • getQuatX

      The X component of the reported Quaternion.
      • Minimum Value: -1.0001220852154804
      • Maximum Value: 1.0
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      QuatX Status Signal Value object
    • getQuatY

      The Y component of the reported Quaternion.
      • Minimum Value: -1.0001220852154804
      • Maximum Value: 1.0
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      QuatY Status Signal Value object
    • getQuatZ

      The Z component of the reported Quaternion.
      • Minimum Value: -1.0001220852154804
      • Maximum Value: 1.0
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      QuatZ Status Signal Value 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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      GravityVectorX Status Signal Value 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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      GravityVectorY Status Signal Value 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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      GravityVectorZ Status Signal Value object
    • getTemperature

      Temperature of the Pigeon 2.
      • Minimum Value: -128.0
      • Maximum Value: 127.99609375
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      Temperature Status Signal Value object
    • getNoMotionEnabled

      Whether the no-motion calibration feature is enabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      NoMotionEnabled Status Signal Value object
    • getNoMotionCount

      The number of times a no-motion event occurred, wraps at 15.
      • Minimum Value: 0
      • Maximum Value: 15
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      NoMotionCount Status Signal Value object
    • getTemperatureCompensationDisabled

      Whether the temperature-compensation feature is disabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      TemperatureCompensationDisabled Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      UpTime Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccumGyroX Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccumGyroY Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccumGyroZ Status Signal Value object
    • getAngularVelocityX

      The angular velocity (ω) of the Pigeon 2 about the X axis.
      • Minimum Value: -1998.048780487805
      • Maximum Value: 1997.987804878049
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AngularVelocityX Status Signal Value object
    • getAngularVelocityY

      The angular velocity (ω) of the Pigeon 2 about the Y axis.
      • Minimum Value: -1998.048780487805
      • Maximum Value: 1997.987804878049
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AngularVelocityY Status Signal Value object
    • getAngularVelocityZ

      The angular velocity (ω) of the Pigeon 2 about the Z axis.
      • Minimum Value: -1998.048780487805
      • Maximum Value: 1997.987804878049
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AngularVelocityZ Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccelerationX Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccelerationY Status Signal Value 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      AccelerationZ Status Signal Value object
    • getSupplyVoltage

      Measured supply voltage to the Pigeon2.
      • Minimum Value: 0.0
      • Maximum Value: 31.99951171875
      • Default Value: 0
      • Units: V
      Default Rates:
      • CAN: 10.0 Hz
      Returns:
      SupplyVoltage Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      MagneticFieldX Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      MagneticFieldY Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      MagneticFieldZ Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      RawMagneticFieldX Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      RawMagneticFieldY Status Signal Value 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
      Default Rates:
      • CAN: 5.0 Hz
      Returns:
      RawMagneticFieldZ Status Signal Value object
    • getFault_Hardware

      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_Hardware Status Signal Value object
    • getStickyFault_Hardware

      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_Hardware Status Signal Value object
    • getFault_Undervoltage

      Device supply voltage dropped to near brownout levels
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_Undervoltage Status Signal Value object
    • getStickyFault_Undervoltage

      Device supply voltage dropped to near brownout levels
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_Undervoltage Status Signal Value object
    • getFault_BootDuringEnable

      Device boot while detecting the enable signal
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootDuringEnable Status Signal Value object
    • getStickyFault_BootDuringEnable

      Device boot while detecting the enable signal
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootDuringEnable Status Signal Value object
    • getFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootupAccelerometer Status Signal Value object
    • getStickyFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootupAccelerometer Status Signal Value object
    • getFault_BootupGyroscope

      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootupGyroscope Status Signal Value object
    • getStickyFault_BootupGyroscope

      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootupGyroscope Status Signal Value object
    • getFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootupMagnetometer Status Signal Value object
    • getStickyFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootupMagnetometer Status Signal Value object
    • getFault_BootIntoMotion

      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootIntoMotion Status Signal Value object
    • getStickyFault_BootIntoMotion

      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootIntoMotion Status Signal Value object
    • getFault_DataAcquiredLate

      Motion stack data acquisition was slower than expected
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_DataAcquiredLate Status Signal Value object
    • getStickyFault_DataAcquiredLate

      Motion stack data acquisition was slower than expected
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_DataAcquiredLate Status Signal Value object
    • getFault_LoopTimeSlow

      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_LoopTimeSlow Status Signal Value object
    • getStickyFault_LoopTimeSlow

      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_LoopTimeSlow Status Signal Value object
    • getFault_SaturatedMagneter

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_SaturatedMagneter Status Signal Value object
    • getStickyFault_SaturatedMagneter

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_SaturatedMagneter Status Signal Value object
    • getFault_SaturatedAccelometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_SaturatedAccelometer Status Signal Value object
    • getStickyFault_SaturatedAccelometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_SaturatedAccelometer Status Signal Value object
    • getFault_SaturatedGyrosscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_SaturatedGyrosscope Status Signal Value object
    • getStickyFault_SaturatedGyrosscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_SaturatedGyrosscope Status Signal Value object
    • setControl

      public StatusCode setControl​(ControlRequest request)
      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

      public StatusCode setYaw​(double newValue, double timeoutSeconds)
      The yaw to set the Pigeon2 to right now.
      Parameters:
      newValue - Value to set to.
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • setYaw

      public StatusCode setYaw​(double newValue)
      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.
      Returns:
      StatusCode of the set command
    • clearStickyFaults

      public StatusCode clearStickyFaults​(double timeoutSeconds)
      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