Class CorePigeon2

Direct Known Subclasses:
Pigeon2

public class CorePigeon2 extends ParentDevice
Class description for the Pigeon 2 IMU sensor that measures orientation.
 // 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());
 
  • 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
    • CorePigeon2

      public CorePigeon2(int deviceId, CANBus canbus)
      Constructs a new Pigeon 2 sensor object.
      Parameters:
      deviceId - ID of the device, as configured in Phoenix Tuner.
      canbus - The CAN bus this device is on.
  • 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:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      VersionMajor Status Signal Object
    • getVersionMajor

      public StatusSignal<Integer> getVersionMajor(boolean refresh)
      App Major Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      VersionMajor Status Signal Object
    • getVersionMinor

      App Minor Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      VersionMinor Status Signal Object
    • getVersionMinor

      public StatusSignal<Integer> getVersionMinor(boolean refresh)
      App Minor Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      VersionMinor Status Signal Object
    • getVersionBugfix

      App Bugfix Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      VersionBugfix Status Signal Object
    • getVersionBugfix

      public StatusSignal<Integer> getVersionBugfix(boolean refresh)
      App Bugfix Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      VersionBugfix Status Signal Object
    • getVersionBuild

      App Build Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      VersionBuild Status Signal Object
    • getVersionBuild

      public StatusSignal<Integer> getVersionBuild(boolean refresh)
      App Build Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      VersionBuild Status Signal Object
    • getVersion

      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

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Version Status Signal Object
    • getVersion

      public StatusSignal<Integer> getVersion(boolean refresh)
      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

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Version Status Signal Object
    • getFaultField

      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 Value: 0
      • Maximum Value: 4294967295
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      FaultField Status Signal Object
    • getFaultField

      public StatusSignal<Integer> getFaultField(boolean refresh)
      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 Value: 0
      • Maximum Value: 4294967295
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      FaultField Status Signal Object
    • getStickyFaultField

      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 Value: 0
      • Maximum Value: 4294967295
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFaultField Status Signal Object
    • getStickyFaultField

      public StatusSignal<Integer> getStickyFaultField(boolean refresh)
      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 Value: 0
      • Maximum Value: 4294967295
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Yaw Status Signal Object
    • getYaw

      public StatusSignal<Angle> getYaw(boolean refresh)
      Current reported yaw of the Pigeon2.
      • Minimum Value: -368640.0
      • Maximum Value: 368639.99725341797
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Pitch Status Signal Object
    • getPitch

      public StatusSignal<Angle> getPitch(boolean refresh)
      Current reported pitch of the Pigeon2.
      • Minimum Value: -90.0
      • Maximum Value: 89.9560546875
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Roll Status Signal Object
    • getRoll

      public StatusSignal<Angle> getRoll(boolean refresh)
      Current reported roll of the Pigeon2.
      • Minimum Value: -180.0
      • Maximum Value: 179.9560546875
      • Default Value: 0
      • Units: deg
      Default Rates:
      • CAN 2.0: 100.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      QuatW Status Signal Object
    • getQuatW

      public StatusSignal<Double> getQuatW(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      QuatX Status Signal Object
    • getQuatX

      public StatusSignal<Double> getQuatX(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      QuatY Status Signal Object
    • getQuatY

      public StatusSignal<Double> getQuatY(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 50.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      QuatZ Status Signal Object
    • getQuatZ

      public StatusSignal<Double> getQuatZ(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      GravityVectorX Status Signal Object
    • getGravityVectorX

      public StatusSignal<Double> getGravityVectorX(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      GravityVectorY Status Signal Object
    • getGravityVectorY

      public StatusSignal<Double> getGravityVectorY(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      GravityVectorZ Status Signal Object
    • getGravityVectorZ

      public StatusSignal<Double> getGravityVectorZ(boolean refresh)
      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 (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      GravityVectorZ Status Signal Object
    • getTemperature

      Temperature of the Pigeon 2.
      • Minimum Value: -128.0
      • Maximum Value: 127.99609375
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Temperature Status Signal Object
    • getTemperature

      public StatusSignal<Temperature> getTemperature(boolean refresh)
      Temperature of the Pigeon 2.
      • Minimum Value: -128.0
      • Maximum Value: 127.99609375
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Temperature Status Signal Object
    • getNoMotionEnabled

      Whether the no-motion calibration feature is enabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      NoMotionEnabled Status Signal Object
    • getNoMotionEnabled

      public StatusSignal<Boolean> getNoMotionEnabled(boolean refresh)
      Whether the no-motion calibration feature is enabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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:
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      NoMotionCount Status Signal Object
    • getNoMotionCount

      public StatusSignal<Double> getNoMotionCount(boolean refresh)
      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: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      NoMotionCount Status Signal Object
    • getTemperatureCompensationDisabled

      Whether the temperature-compensation feature is disabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      TemperatureCompensationDisabled Status Signal Object
    • getTemperatureCompensationDisabled

      Whether the temperature-compensation feature is disabled.
      • Default Value: 0
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      UpTime Status Signal Object
    • getUpTime

      public StatusSignal<Time> getUpTime(boolean refresh)
      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: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccumGyroX Status Signal Object
    • getAccumGyroX

      public StatusSignal<Angle> getAccumGyroX(boolean refresh)
      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: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccumGyroY Status Signal Object
    • getAccumGyroY

      public StatusSignal<Angle> getAccumGyroY(boolean refresh)
      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: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccumGyroZ Status Signal Object
    • getAccumGyroZ

      public StatusSignal<Angle> getAccumGyroZ(boolean refresh)
      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: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      AccumGyroZ Status Signal Object
    • getAngularVelocityXWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityXWorld Status Signal Object
    • getAngularVelocityXWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      AngularVelocityXWorld Status Signal Object
    • getAngularVelocityYWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityYWorld Status Signal Object
    • getAngularVelocityYWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      AngularVelocityYWorld Status Signal Object
    • getAngularVelocityZWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityZWorld Status Signal Object
    • getAngularVelocityZWorld

      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 Value: 2047.99609375
      • Default Value: 0
      • Units: dps
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccelerationX 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccelerationY 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AccelerationZ 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
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Returns:
      SupplyVoltage Status Signal Object
    • getSupplyVoltage

      public StatusSignal<Voltage> getSupplyVoltage(boolean refresh)
      Measured supply voltage to the Pigeon2.
      • Minimum Value: 0.0
      • Maximum Value: 31.99951171875
      • Default Value: 0
      • Units: V
      Default Rates:
      • CAN 2.0: 4.0 Hz
      • CAN FD: 100.0 Hz (TimeSynced with Pro)

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityXDevice 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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityYDevice 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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      AngularVelocityZDevice 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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      MagneticFieldX Status Signal Object
    • getMagneticFieldX

      public StatusSignal<Double> getMagneticFieldX(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      MagneticFieldY Status Signal Object
    • getMagneticFieldY

      public StatusSignal<Double> getMagneticFieldY(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      MagneticFieldZ Status Signal Object
    • getMagneticFieldZ

      public StatusSignal<Double> getMagneticFieldZ(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      RawMagneticFieldX Status Signal Object
    • getRawMagneticFieldX

      public StatusSignal<Double> getRawMagneticFieldX(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      RawMagneticFieldY Status Signal Object
    • getRawMagneticFieldY

      public StatusSignal<Double> getRawMagneticFieldY(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      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
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      RawMagneticFieldZ Status Signal Object
    • getRawMagneticFieldZ

      public StatusSignal<Double> getRawMagneticFieldZ(boolean refresh)
      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: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      RawMagneticFieldZ Status Signal Object
    • getIsProLicensed

      Whether the device is Phoenix Pro licensed.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      IsProLicensed Status Signal Object
    • getIsProLicensed

      public StatusSignal<Boolean> getIsProLicensed(boolean refresh)
      Whether the device is Phoenix Pro licensed.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      IsProLicensed Status Signal Object
    • getFault_Hardware

      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_Hardware Status Signal Object
    • getFault_Hardware

      public StatusSignal<Boolean> getFault_Hardware(boolean refresh)
      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_Hardware Status Signal Object
    • getStickyFault_Hardware

      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_Hardware Status Signal Object
    • getStickyFault_Hardware

      public StatusSignal<Boolean> getStickyFault_Hardware(boolean refresh)
      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_Hardware Status Signal Object
    • 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.

      Returns:
      Fault_Undervoltage Status Signal Object
    • getFault_Undervoltage

      public StatusSignal<Boolean> getFault_Undervoltage(boolean refresh)
      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.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_Undervoltage Status Signal Object
    • 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.

      Returns:
      StickyFault_Undervoltage Status Signal Object
    • 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.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_Undervoltage Status Signal Object
    • 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.

      Returns:
      Fault_BootDuringEnable Status Signal Object
    • getFault_BootDuringEnable

      public StatusSignal<Boolean> getFault_BootDuringEnable(boolean refresh)
      Device boot while detecting the enable signal
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_BootDuringEnable Status Signal Object
    • 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.

      Returns:
      StickyFault_BootDuringEnable Status Signal Object
    • 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.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_BootDuringEnable Status Signal Object
    • getFault_UnlicensedFeatureInUse

      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_UnlicensedFeatureInUse Status Signal Object
    • getFault_UnlicensedFeatureInUse

      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_UnlicensedFeatureInUse Status Signal Object
    • getStickyFault_UnlicensedFeatureInUse

      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_UnlicensedFeatureInUse Status Signal Object
    • getStickyFault_UnlicensedFeatureInUse

      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_UnlicensedFeatureInUse Status Signal Object
    • getFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_BootupAccelerometer Status Signal Object
    • getFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_BootupAccelerometer Status Signal Object
    • getStickyFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_BootupAccelerometer Status Signal Object
    • getStickyFault_BootupAccelerometer

      Bootup checks failed: Accelerometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_BootupAccelerometer Status Signal Object
    • getFault_BootupGyroscope

      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_BootupGyroscope Status Signal Object
    • getFault_BootupGyroscope

      public StatusSignal<Boolean> getFault_BootupGyroscope(boolean refresh)
      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_BootupGyroscope Status Signal Object
    • getStickyFault_BootupGyroscope

      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_BootupGyroscope Status Signal Object
    • getStickyFault_BootupGyroscope

      Bootup checks failed: Gyroscope
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_BootupGyroscope Status Signal Object
    • getFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_BootupMagnetometer Status Signal Object
    • getFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_BootupMagnetometer Status Signal Object
    • getStickyFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_BootupMagnetometer Status Signal Object
    • getStickyFault_BootupMagnetometer

      Bootup checks failed: Magnetometer
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_BootupMagnetometer Status Signal Object
    • getFault_BootIntoMotion

      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_BootIntoMotion Status Signal Object
    • getFault_BootIntoMotion

      public StatusSignal<Boolean> getFault_BootIntoMotion(boolean refresh)
      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_BootIntoMotion Status Signal Object
    • getStickyFault_BootIntoMotion

      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_BootIntoMotion Status Signal Object
    • getStickyFault_BootIntoMotion

      Motion Detected during bootup.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_BootIntoMotion Status Signal Object
    • 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.

      Returns:
      Fault_DataAcquiredLate Status Signal Object
    • getFault_DataAcquiredLate

      public StatusSignal<Boolean> getFault_DataAcquiredLate(boolean refresh)
      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.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_DataAcquiredLate Status Signal Object
    • 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.

      Returns:
      StickyFault_DataAcquiredLate Status Signal Object
    • 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.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_DataAcquiredLate Status Signal Object
    • getFault_LoopTimeSlow

      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_LoopTimeSlow Status Signal Object
    • getFault_LoopTimeSlow

      public StatusSignal<Boolean> getFault_LoopTimeSlow(boolean refresh)
      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_LoopTimeSlow Status Signal Object
    • getStickyFault_LoopTimeSlow

      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_LoopTimeSlow Status Signal Object
    • getStickyFault_LoopTimeSlow

      Motion stack loop time was slower than expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_LoopTimeSlow Status Signal Object
    • getFault_SaturatedMagnetometer

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_SaturatedMagnetometer Status Signal Object
    • getFault_SaturatedMagnetometer

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_SaturatedMagnetometer Status Signal Object
    • getStickyFault_SaturatedMagnetometer

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_SaturatedMagnetometer Status Signal Object
    • getStickyFault_SaturatedMagnetometer

      Magnetometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_SaturatedMagnetometer Status Signal Object
    • getFault_SaturatedAccelerometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_SaturatedAccelerometer Status Signal Object
    • getFault_SaturatedAccelerometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_SaturatedAccelerometer Status Signal Object
    • getStickyFault_SaturatedAccelerometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_SaturatedAccelerometer Status Signal Object
    • getStickyFault_SaturatedAccelerometer

      Accelerometer values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_SaturatedAccelerometer Status Signal Object
    • getFault_SaturatedGyroscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      Fault_SaturatedGyroscope Status Signal Object
    • getFault_SaturatedGyroscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      Fault_SaturatedGyroscope Status Signal Object
    • getStickyFault_SaturatedGyroscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Returns:
      StickyFault_SaturatedGyroscope Status Signal Object
    • getStickyFault_SaturatedGyroscope

      Gyroscope values are saturated
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz

      This refreshes and returns a cached StatusSignal object.

      Parameters:
      refresh - Whether to refresh the StatusSignal before returning it; defaults to true
      Returns:
      StickyFault_SaturatedGyroscope Status Signal Object
    • setControl

      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 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)
      The yaw to set the Pigeon2 to right now.

      This will wait up to 0.100 seconds (100ms) by default.

      Parameters:
      newValue - Value to set to. Units are in deg.
      Returns:
      StatusCode of the set command
    • setYaw

      public StatusCode setYaw(double newValue, double timeoutSeconds)
      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

      public StatusCode setYaw(Angle newValue)
      The yaw to set the Pigeon2 to right now.

      This will wait up to 0.100 seconds (100ms) by default.

      Parameters:
      newValue - Value to set to. Units are in deg.
      Returns:
      StatusCode of the set command
    • setYaw

      public StatusCode setYaw(Angle newValue, double timeoutSeconds)
      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
    • 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.100 seconds (100ms) by default.

      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
    • clearStickyFault_Hardware

      Clear sticky fault: Hardware fault occurred

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_Hardware

      public StatusCode clearStickyFault_Hardware(double timeoutSeconds)
      Clear sticky fault: Hardware fault occurred
      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 levels

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_Undervoltage

      public StatusCode clearStickyFault_Undervoltage(double timeoutSeconds)
      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_BootDuringEnable

      Clear sticky fault: Device boot while detecting the enable signal

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_BootDuringEnable

      public StatusCode clearStickyFault_BootDuringEnable(double timeoutSeconds)
      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_UnlicensedFeatureInUse

      Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_UnlicensedFeatureInUse

      public StatusCode clearStickyFault_UnlicensedFeatureInUse(double timeoutSeconds)
      Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
      Parameters:
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupAccelerometer

      Clear sticky fault: Bootup checks failed: Accelerometer

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupAccelerometer

      public StatusCode clearStickyFault_BootupAccelerometer(double timeoutSeconds)
      Clear sticky fault: Bootup checks failed: Accelerometer
      Parameters:
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupGyroscope

      Clear sticky fault: Bootup checks failed: Gyroscope

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupGyroscope

      public StatusCode clearStickyFault_BootupGyroscope(double timeoutSeconds)
      Clear sticky fault: Bootup checks failed: Gyroscope
      Parameters:
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupMagnetometer

      Clear sticky fault: Bootup checks failed: Magnetometer

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_BootupMagnetometer

      public StatusCode clearStickyFault_BootupMagnetometer(double timeoutSeconds)
      Clear sticky fault: Bootup checks failed: Magnetometer
      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.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_BootIntoMotion

      public StatusCode clearStickyFault_BootIntoMotion(double timeoutSeconds)
      Clear sticky fault: Motion Detected during bootup.
      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 expected

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_DataAcquiredLate

      public StatusCode clearStickyFault_DataAcquiredLate(double timeoutSeconds)
      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_LoopTimeSlow

      Clear sticky fault: Motion stack loop time was slower than expected.

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_LoopTimeSlow

      public StatusCode clearStickyFault_LoopTimeSlow(double timeoutSeconds)
      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_SaturatedMagnetometer

      Clear sticky fault: Magnetometer values are saturated

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_SaturatedMagnetometer

      public StatusCode clearStickyFault_SaturatedMagnetometer(double timeoutSeconds)
      Clear sticky fault: Magnetometer 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 saturated

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_SaturatedAccelerometer

      public StatusCode clearStickyFault_SaturatedAccelerometer(double timeoutSeconds)
      Clear sticky fault: Accelerometer 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 saturated

      This will wait up to 0.100 seconds (100ms) by default.

      Returns:
      StatusCode of the set command
    • clearStickyFault_SaturatedGyroscope

      public StatusCode clearStickyFault_SaturatedGyroscope(double timeoutSeconds)
      Clear sticky fault: Gyroscope values are saturated
      Parameters:
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command