Class BasePigeon

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

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

    • BasePigeon

      public BasePigeon​(int deviceNumber, String version, String canbus)
      Create a Pigeon object that communicates with Pigeon on CAN Bus.
      Parameters:
      deviceNumber - CAN Device Id of Pigeon [0,62]
      version - Version of the PigeonIMU
      canbus - Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
    • BasePigeon

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

      protected BasePigeon​(TalonSRX talonSrx)
  • Method Details

    • DestroyObject

      Destructor for Pigeon
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getSimCollection

      Returns:
      object that can set simulation inputs.
    • setYaw

      public ErrorCode setYaw​(double angleDeg, int timeoutMs)
      Sets the Yaw register to the specified value.
      Parameters:
      angleDeg - New yaw in degrees [+/- 368,640 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.
    • setYaw

      public ErrorCode setYaw​(double angleDeg)
      Sets the Yaw register to the specified value.
      Parameters:
      angleDeg - New yaw in degrees [+/- 368,640 degrees]
      Returns:
      Error Code generated by function. 0 indicates no error.
    • addYaw

      public ErrorCode addYaw​(double angleDeg, int timeoutMs)
      Atomically add to the Yaw register.
      Parameters:
      angleDeg - Degrees to add to the Yaw 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.
    • addYaw

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

      public ErrorCode setYawToCompass​(int timeoutMs)
      Sets the Yaw 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.
    • setYawToCompass

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

      public ErrorCode setAccumZAngle​(double angleDeg, int timeoutMs)
      Sets the AccumZAngle.
      Parameters:
      angleDeg - Degrees to set AccumZAngle 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.
    • setAccumZAngle

      public ErrorCode setAccumZAngle​(double angleDeg)
      Sets the AccumZAngle.
      Parameters:
      angleDeg - Degrees to set AccumZAngle to.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getLastError

      Call GetLastError() generated by this object. Not all functions return an error code but can potentially report errors. This function can be used to retrieve those error codes.
      Returns:
      The last ErrorCode generated.
    • get6dQuaternion

      public ErrorCode get6dQuaternion​(double[] wxyz)
      Get 6d Quaternion data.
      Parameters:
      wxyz - Array to fill with quaternion data w[0], x[1], y[2], z[3]
      Returns:
      The last ErrorCode generated.
    • getYawPitchRoll

      public ErrorCode getYawPitchRoll​(double[] ypr_deg)
      Get Yaw, Pitch, and Roll data.
      Parameters:
      ypr_deg - Array to fill with yaw[0], pitch[1], and roll[2] data. Yaw is within [-368,640, +368,640] degrees. Pitch is within [-90,+90] degrees. Roll is within [-90,+90] degrees.
      Returns:
      The last ErrorCode generated.
    • getYaw

      public double getYaw()
      Get the yaw from the Pigeon
      Returns:
      Yaw
    • getPitch

      public double getPitch()
      Get the pitch from the Pigeon
      Returns:
      Pitch
    • getRoll

      public double getRoll()
      Get the roll from the Pigeon
      Returns:
      Roll
    • getAccumGyro

      public ErrorCode getAccumGyro​(double[] xyz_deg)
      Get AccumGyro data. AccumGyro is the integrated gyro value on each axis.
      Parameters:
      xyz_deg - Array to fill with x[0], y[1], and z[2] AccumGyro data
      Returns:
      The last ErrorCode generated.
    • getAbsoluteCompassHeading

      public double getAbsoluteCompassHeading()
      Get the absolute compass heading.
      Returns:
      compass heading [0,360) degrees.
    • getCompassHeading

      public double getCompassHeading()
      Get the continuous compass heading.
      Returns:
      continuous compass heading [-23040, 23040) degrees. Use SetCompassHeading to modify the wrap-around portion.
    • getCompassFieldStrength

      public double getCompassFieldStrength()
      Gets the compass' measured magnetic field strength.
      Returns:
      field strength in Microteslas (uT).
    • getTemp

      public double getTemp()
      Gets the temperature of the pigeon.
      Returns:
      Temperature in ('C)
    • getUpTime

      public int getUpTime()
      Gets the current Pigeon uptime.
      Returns:
      How long has Pigeon been running in whole seconds. Value caps at 255.
    • getRawMagnetometer

      public ErrorCode getRawMagnetometer​(short[] rm_xyz)
      Get Raw Magnetometer data.
      Parameters:
      rm_xyz - Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.
      Returns:
      The last ErrorCode generated.
    • getBiasedMagnetometer

      public ErrorCode getBiasedMagnetometer​(short[] bm_xyz)
      Get Biased Magnetometer data.
      Parameters:
      bm_xyz - Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.
      Returns:
      The last ErrorCode generated.
    • getBiasedAccelerometer

      public ErrorCode getBiasedAccelerometer​(short[] ba_xyz)
      Get Biased Accelerometer data.
      Parameters:
      ba_xyz - Array to fill with x[0], y[1], and z[2] data. These are in fixed point notation Q2.14. eg. 16384 = 1G
      Returns:
      The last ErrorCode generated.
    • getRawGyro

      public ErrorCode getRawGyro​(double[] xyz_dps)
      Get Raw Gyro data.
      Parameters:
      xyz_dps - Array to fill with x[0], y[1], and z[2] data in degrees per second.
      Returns:
      The last ErrorCode generated.
    • getResetCount

      public int getResetCount()
      Returns:
      number of times Pigeon Reset
    • getResetFlags

      public int getResetFlags()
      Returns:
      Reset flags for Pigeon
    • getFirmwareVersion

      public int getFirmwareVersion()
      Gets the firmware version of the device.
      Returns:
      param holds the firmware version of the device. Device must be powered cycled at least once.
    • hasResetOccurred

      public boolean hasResetOccurred()
      Returns:
      true iff a reset has occurred since last call.
    • configSetCustomParam

      public ErrorCode configSetCustomParam​(int newValue, int paramIndex, int timeoutMs)
      Sets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
      Parameters:
      newValue - Value for custom parameter.
      paramIndex - Index of custom parameter. [0-1]
      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.
    • configSetCustomParam

      public ErrorCode configSetCustomParam​(int newValue, int paramIndex)
      Sets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
      Parameters:
      newValue - Value for custom parameter.
      paramIndex - Index of custom parameter. [0-1]
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configGetCustomParam

      public int configGetCustomParam​(int paramIndex, int timoutMs)
      Gets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
      Parameters:
      paramIndex - Index of custom parameter. [0-1]
      timoutMs - 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:
      Value of the custom param.
    • configGetCustomParam

      public int configGetCustomParam​(int paramIndex)
      Gets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
      Parameters:
      paramIndex - Index of custom parameter. [0-1]
      Returns:
      Value of the custom param.
    • configSetParameter

      public ErrorCode configSetParameter​(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs)
      Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      value - Value of parameter.
      subValue - Subvalue for parameter. Maximum value of 255.
      ordinal - Ordinal of parameter.
      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.
    • configSetParameter

      public ErrorCode configSetParameter​(ParamEnum param, double value, int subValue, int ordinal)
      Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      value - Value of parameter.
      subValue - Subvalue for parameter. Maximum value of 255.
      ordinal - Ordinal of parameter.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configSetParameter

      public ErrorCode configSetParameter​(int param, double value, int subValue, int ordinal, int timeoutMs)
      Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      value - Value of parameter.
      subValue - Subvalue for parameter. Maximum value of 255.
      ordinal - Ordinal of parameter.
      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.
    • configSetParameter

      public ErrorCode configSetParameter​(int param, double value, int subValue, int ordinal)
      Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      value - Value of parameter.
      subValue - Subvalue for parameter. Maximum value of 255.
      ordinal - Ordinal of parameter.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configGetParameter

      public double configGetParameter​(ParamEnum param, int ordinal, int timeoutMs)
      Gets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      ordinal - Ordinal of parameter.
      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:
      Value of parameter.
    • configGetParameter

      public double configGetParameter​(ParamEnum param, int ordinal)
      Gets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.
      Parameters:
      param - Parameter enumeration.
      ordinal - Ordinal of parameter.
      Returns:
      Value of parameter.
    • configGetParameter

      public double configGetParameter​(int param, int ordinal, int timeoutMs)
      Gets a parameter.
      Parameters:
      param - Parameter enumeration.
      ordinal - Ordinal of parameter.
      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:
      Value of parameter.
    • configGetParameter

      public double configGetParameter​(int param, int ordinal)
      Gets a parameter.
      Parameters:
      param - Parameter enumeration.
      ordinal - Ordinal of parameter.
      Returns:
      Value of parameter.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs)
      Sets the period of the given status frame.
      Parameters:
      statusFrame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      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.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(PigeonIMU_StatusFrame statusFrame, int periodMs)
      Sets the period of the given status frame.
      Parameters:
      statusFrame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(int statusFrame, int periodMs, int timeoutMs)
      Sets the period of the given status frame.
      Parameters:
      statusFrame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      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.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(int statusFrame, int periodMs)
      Sets the period of the given status frame.
      Parameters:
      statusFrame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getStatusFramePeriod

      public int getStatusFramePeriod​(PigeonIMU_StatusFrame frame, int timeoutMs)
      Gets the period of the given status frame.
      Parameters:
      frame - Frame to get the period of.
      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:
      Period of the given status frame.
    • getStatusFramePeriod

      Gets the period of the given status frame.
      Parameters:
      frame - Frame to get the period of.
      Returns:
      Period of the given status frame.
    • setControlFramePeriod

      public ErrorCode setControlFramePeriod​(PigeonIMU_ControlFrame frame, int periodMs)
      Sets the period of the given control frame.
      Parameters:
      frame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setControlFramePeriod

      public ErrorCode setControlFramePeriod​(int frame, int periodMs)
      Sets the period of the given control frame.
      Parameters:
      frame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • clearStickyFaults

      public ErrorCode clearStickyFaults​(int timeoutMs)
      Clears the Sticky Faults
      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.
    • clearStickyFaults

      Clears the Sticky Faults
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getDeviceID

      public int getDeviceID()
      Returns:
      The Device Number
    • configAllSettings

      public ErrorCode configAllSettings​(PigeonIMUConfiguration allConfigs, int timeoutMs)
      Configures all persistent settings.
      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).
      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.
      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).
      Parameters:
      allConfigs - Object with all of the persistant settings
    • configFactoryDefault

      public ErrorCode configFactoryDefault​(int timeoutMs)
      Configures all persistent settings to defaults.
      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).
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getHandle

      public long getHandle()