Class PigeonIMU

java.lang.Object
com.ctre.phoenix.sensors.BasePigeon
com.ctre.phoenix.sensors.PigeonIMU
Direct Known Subclasses:
WPI_PigeonIMU

public class PigeonIMU
extends BasePigeon
Pigeon IMU Class. Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
  • Constructor Details

    • PigeonIMU

      public PigeonIMU​(int deviceNumber)
      Create a Pigeon object that communicates with Pigeon on CAN Bus.
      Parameters:
      deviceNumber - CAN Device Id of Pigeon [0,62]
    • PigeonIMU

      public PigeonIMU​(TalonSRX talonSrx)
      Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to a Talon on CAN Bus.
      Parameters:
      talonSrx - Object for the TalonSRX connected via ribbon cable.
  • Method Details

    • setFusedHeading

      public ErrorCode setFusedHeading​(double angleDeg, int timeoutMs)
      Sets the Fused Heading to the specified value.
      Parameters:
      angleDeg - New fused-heading in degrees [+/- 23,040 degrees]
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setFusedHeading

      public ErrorCode setFusedHeading​(double angleDeg)
      Sets the Fused Heading to the specified value.
      Parameters:
      angleDeg - New fused-heading in degrees [+/- 23,040 degrees]
      Returns:
      Error Code generated by function. 0 indicates no error.
    • addFusedHeading

      public ErrorCode addFusedHeading​(double angleDeg, int timeoutMs)
      Atomically add to the Fused Heading register.
      Parameters:
      angleDeg - Degrees to add to the Fused Heading register.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • addFusedHeading

      public ErrorCode addFusedHeading​(double angleDeg)
      Atomically add to the Fused Heading register.
      Parameters:
      angleDeg - Degrees to add to the Fused Heading register
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setFusedHeadingToCompass

      public ErrorCode setFusedHeadingToCompass​(int timeoutMs)
      Sets the Fused Heading register to match the current compass value.
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setFusedHeadingToCompass

      Sets the Fused Heading register to match the current compass value.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setTemperatureCompensationDisable

      public ErrorCode setTemperatureCompensationDisable​(boolean bTempCompDisable, int timeoutMs)
      Disable/Enable Temp compensation. Pigeon has this on/False at boot.
      Parameters:
      bTempCompDisable - Set to "False" to enable temperature compensation.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setTemperatureCompensationDisable

      public ErrorCode setTemperatureCompensationDisable​(boolean bTempCompDisable)
      Disable/Enable Temp compensation. Pigeon has this on/False at boot.
      Parameters:
      bTempCompDisable - Set to "False" to enable temperature compensation.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setCompassDeclination

      public ErrorCode setCompassDeclination​(double angleDegOffset, int timeoutMs)
      Set the declination for compass. Declination is the difference between Earth Magnetic north, and the geographic "True North".
      Parameters:
      angleDegOffset - Degrees to set Compass Declination to.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setCompassDeclination

      public ErrorCode setCompassDeclination​(double angleDegOffset)
      Set the declination for compass. Declination is the difference between Earth Magnetic north, and the geographic "True North".
      Parameters:
      angleDegOffset - Degrees to set Compass Declination to.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setCompassAngle

      public ErrorCode setCompassAngle​(double angleDeg, int timeoutMs)
      Sets the compass angle. Although compass is absolute [0,360) degrees, the continuous compass register holds the wrap-arounds.
      Parameters:
      angleDeg - Degrees to set continuous compass angle to.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setCompassAngle

      public ErrorCode setCompassAngle​(double angleDeg)
      Sets the compass angle. Although compass is absolute [0,360) degrees, the continuous compass register holds the wrap-arounds.
      Parameters:
      angleDeg - Degrees to set continuous compass angle to.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • enterCalibrationMode

      public ErrorCode enterCalibrationMode​(PigeonIMU.CalibrationMode calMode, int timeoutMs)
      Enters the Calbration mode. See the Pigeon IMU documentation for More information on Calibration. Note that you can instead use Phoenix Tuner to accomplish this. Note you should NOT be calling this during normal robot operation.
      Parameters:
      calMode - Calibration to execute
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • enterCalibrationMode

      Enters the Calbration mode. See the Pigeon IMU documentation for More information on Calibration. Note that you can instead use Phoenix Tuner to accomplish this. Note you should not be using this in your normal robot application.
      Parameters:
      calMode - Calibration to execute
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getGeneralStatus

      Get the status of the current (or previousley complete) calibration.
      Parameters:
      toFill - Container for the status information.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getState

      Gets the current Pigeon state
      Returns:
      PigeonState enum
    • getFusedHeading

      public double getFusedHeading​(PigeonIMU.FusionStatus toFill)
      Get the current Fusion Status (including fused heading)
      Parameters:
      toFill - object reference to fill with fusion status flags. Caller may pass null if flags are not needed.
      Returns:
      The fused heading in degrees.
    • getFusedHeading

      public double getFusedHeading()
      Gets the Fused Heading
      Returns:
      The fused heading in degrees.
    • getAccelerometerAngles

      public ErrorCode getAccelerometerAngles​(double[] tiltAngles)
      Get Accelerometer tilt angles.
      Parameters:
      tiltAngles - Array to fill with x[0], y[1], and z[2] angles in degrees.
      Returns:
      The last ErrorCode generated.
    • configAllSettings

      public ErrorCode configAllSettings​(PigeonIMUConfiguration allConfigs, int timeoutMs)
      Configures all persistent settings.
      Overrides:
      configAllSettings in class BasePigeon
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configAllSettings

      Configures all persistent settings (overloaded so timeoutMs is 50 ms).
      Overrides:
      configAllSettings in class BasePigeon
      Parameters:
      allConfigs - Object with all of the persistant settings
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getAllConfigs

      public void getAllConfigs​(PigeonIMUConfiguration allConfigs, int timeoutMs)
      Gets all persistant settings.
      Overrides:
      getAllConfigs in class BasePigeon
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
    • getAllConfigs

      public void getAllConfigs​(PigeonIMUConfiguration allConfigs)
      Gets all persistant settings (overloaded so timeoutMs is 50 ms).
      Overrides:
      getAllConfigs in class BasePigeon
      Parameters:
      allConfigs - Object with all of the persistant settings
    • configFactoryDefault

      public ErrorCode configFactoryDefault​(int timeoutMs)
      Configures all persistent settings to defaults.
      Overrides:
      configFactoryDefault in class BasePigeon
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configFactoryDefault

      Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).
      Overrides:
      configFactoryDefault in class BasePigeon
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getFaults

      public ErrorCode getFaults​(PigeonIMU_Faults toFill)
      Gets the fault status
      Parameters:
      toFill - Container for fault statuses.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getStickyFaults

      Gets the sticky fault status
      Parameters:
      toFill - Container for sticky fault statuses.
      Returns:
      Error Code generated by function. 0 indicates no error.