Class CoreCANcoder

Direct Known Subclasses:
CANcoder

@Deprecated(forRemoval=true)
public class CoreCANcoder
extends ParentDevice
Deprecated, for removal: This API element is subject to removal in a future version.
Classes in the phoenixpro package will be removed in 2024. Users should instead use classes from the phoenix6 package.
Class for CANcoder, a CAN based magnetic encoder that provides absolute and relative position along with filtered velocity.
  • Constructor Details

    • CoreCANcoder

      @Deprecated(forRemoval=true) public CoreCANcoder​(int deviceId)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Classes in the phoenixpro package will be removed in 2024. Users should instead use classes from the phoenix6 package.
      Constructs a new CANcoder 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.
    • CoreCANcoder

      @Deprecated(forRemoval=true) public CoreCANcoder​(int deviceId, String canbus)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Classes in the phoenixpro package will be removed in 2024. Users should instead use classes from the phoenix6 package.
      Constructs a new CANcoder object.
      Parameters:
      deviceId - ID of the device, as configured in Phoenix Tuner.
      canbus - Name of the CAN bus this device is on. Possible CAN bus strings are:
      • "rio" for the native roboRIO CAN bus
      • CANivore name or serial number
      • SocketCAN interface (non-FRC Linux only)
      • "*" for any CANivore seen by the program
      • empty string (default) to select the default for the system:
        • "rio" on roboRIO
        • "can0" on Linux
        • "*" on Windows
  • Method Details

    • reportIfTooOld

      protected void reportIfTooOld()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Specified by:
      reportIfTooOld in class ParentDevice
    • hasResetOccurred

      public boolean hasResetOccurred()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns:
      true if device has reset since the previous call of this routine.
    • getConfigurator

      Deprecated, for removal: This API element is subject to removal in a future version.
      Gets the configurator to use with this device's configs
      Returns:
      Configurator for this object
    • getSimState

      Deprecated, for removal: This API element is subject to removal in a future version.
      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

      Deprecated, for removal: This API element is subject to removal in a future version.
      App Major Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionMajor Status Signal Value object
    • getVersionMinor

      Deprecated, for removal: This API element is subject to removal in a future version.
      App Minor Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionMinor Status Signal Value object
    • getVersionBugfix

      Deprecated, for removal: This API element is subject to removal in a future version.
      App Bugfix Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionBugfix Status Signal Value object
    • getVersionBuild

      Deprecated, for removal: This API element is subject to removal in a future version.
      App Build Version number.
      • Minimum Value: 0
      • Maximum Value: 255
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      VersionBuild Status Signal Value object
    • getVersion

      Deprecated, for removal: This API element is subject to removal in a future version.
      Full Version. The format is a four byte value.

      Full Version of firmware in device. The format is a four byte value.

      • Minimum Value: 0
      • Maximum Value: 4294967295
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Version Status Signal Value object
    • getFaultField

      Deprecated, for removal: This API element is subject to removal in a future version.
      Integer representing all faults

      This returns the fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetFault_*() methods instead.

      • Minimum Value: 0
      • Maximum Value: 1048575
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      FaultField Status Signal Value object
    • getStickyFaultField

      Deprecated, for removal: This API element is subject to removal in a future version.
      Integer representing all sticky faults

      This returns the persistent "sticky" fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetStickyFault_*() methods instead.

      • Minimum Value: 0
      • Maximum Value: 1048575
      • Default Value: 0
      • Units:
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFaultField Status Signal Value object
    • getVelocity

      Deprecated, for removal: This API element is subject to removal in a future version.
      Velocity of device.
      • Minimum Value: -512.0
      • Maximum Value: 511.998046875
      • Default Value: 0
      • Units: rotations per second
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      Velocity Status Signal Value object
    • getPosition

      Deprecated, for removal: This API element is subject to removal in a future version.
      Position of device.
      • Minimum Value: -16384.0
      • Maximum Value: 16383.999755859375
      • Default Value: 0
      • Units: rotations
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      Position Status Signal Value object
    • getAbsolutePosition

      Deprecated, for removal: This API element is subject to removal in a future version.
      Absolute Position of device. The possible range is documented below, however the exact expected range is determined by the AbsoluteSensorRange.
      • Minimum Value: -0.5
      • Maximum Value: 0.999755859375
      • Default Value: 0
      • Units: rotations
      Default Rates:
      • CAN: 100.0 Hz
      Returns:
      AbsolutePosition Status Signal Value object
    • getUnfilteredVelocity

      Deprecated, for removal: This API element is subject to removal in a future version.
      The unfiltered velocity reported by CANcoder.

      This is the unfiltered velocity reported by CANcoder. This signal does not use the fusing algorithm. It is also not timesynced. If you wish to use a signal with timesync, use Velocity.

      • Minimum Value: -8000.0
      • Maximum Value: 7999.755859375
      • Default Value: 0
      • Units: rotations per second
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      UnfilteredVelocity Status Signal Value object
    • getPositionSinceBoot

      Deprecated, for removal: This API element is subject to removal in a future version.
      The relative position reported by the CANcoder since boot.

      This is the total displacement reported by CANcoder since power up. This signal is relative and is not influenced by the fusing algorithm. It is also not timesynced. If you wish to use a signal with timesync, use Position.

      • Minimum Value: -16384.0
      • Maximum Value: 16383.999755859375
      • Default Value: 0
      • Units: rotations
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      PositionSinceBoot Status Signal Value object
    • getSupplyVoltage

      Deprecated, for removal: This API element is subject to removal in a future version.
      Measured supply voltage to the CANcoder.
      • Minimum Value: 4
      • Maximum Value: 16.75
      • Default Value: 4
      • Units: V
      Default Rates:
      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      SupplyVoltage Status Signal Value object
    • getMagnetHealth

      Deprecated, for removal: This API element is subject to removal in a future version.
      Magnet health as measured by CANcoder.

      Magnet health as measured by CANcoder. Red indicates too close or too far, Orange is adequate but with reduced accuracy, green is ideal. Invalid means the accuracy cannot be determined. Default Rates:

      • CAN 2.0: 10.0 Hz
      • CAN FD: 100.0 Hz
      Returns:
      MagnetHealth Status Signal Value object
    • getFault_Hardware

      Deprecated, for removal: This API element is subject to removal in a future version.
      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_Hardware Status Signal Value object
    • getStickyFault_Hardware

      Deprecated, for removal: This API element is subject to removal in a future version.
      Hardware fault occurred
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_Hardware Status Signal Value object
    • getFault_Undervoltage

      Deprecated, for removal: This API element is subject to removal in a future version.
      Device supply voltage dropped to near brownout levels
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_Undervoltage Status Signal Value object
    • getStickyFault_Undervoltage

      Deprecated, for removal: This API element is subject to removal in a future version.
      Device supply voltage dropped to near brownout levels
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_Undervoltage Status Signal Value object
    • getFault_BootDuringEnable

      Deprecated, for removal: This API element is subject to removal in a future version.
      Device boot while detecting the enable signal
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BootDuringEnable Status Signal Value object
    • getStickyFault_BootDuringEnable

      Deprecated, for removal: This API element is subject to removal in a future version.
      Device boot while detecting the enable signal
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BootDuringEnable Status Signal Value object
    • getFault_UnlicensedFeatureInUse

      Deprecated, for removal: This API element is subject to removal in a future version.
      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_UnlicensedFeatureInUse Status Signal Value object
    • getStickyFault_UnlicensedFeatureInUse

      Deprecated, for removal: This API element is subject to removal in a future version.
      An unlicensed feature is in use, device may not behave as expected.
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_UnlicensedFeatureInUse Status Signal Value object
    • getFault_BadMagnet

      Deprecated, for removal: This API element is subject to removal in a future version.
      The magnet distance is not correct or magnet is missing
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      Fault_BadMagnet Status Signal Value object
    • getStickyFault_BadMagnet

      Deprecated, for removal: This API element is subject to removal in a future version.
      The magnet distance is not correct or magnet is missing
      • Default Value: False
      Default Rates:
      • CAN: 4.0 Hz
      Returns:
      StickyFault_BadMagnet Status Signal Value object
    • setControl

      public StatusCode setControl​(ControlRequest request)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Control motor with generic control request object.

      User must make sure the specified object is castable to a valid control request, otherwise this function will fail at run-time and return the NotSupported StatusCode

      Parameters:
      request - Control object to request of the device
      Returns:
      Status Code of the request, 0 is OK
    • setPosition

      public StatusCode setPosition​(double newValue, double timeoutSeconds)
      Deprecated, for removal: This API element is subject to removal in a future version.
      The position to set the sensor position to right now.
      Parameters:
      newValue - Value to set to.
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • setPosition

      public StatusCode setPosition​(double newValue)
      Deprecated, for removal: This API element is subject to removal in a future version.
      The position to set the sensor position to right now.

      This will wait up to 0.050 seconds (50ms) by default.

      Parameters:
      newValue - Value to set to.
      Returns:
      StatusCode of the set command
    • clearStickyFaults

      public StatusCode clearStickyFaults​(double timeoutSeconds)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Clear the sticky faults in the device.

      This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.

      Parameters:
      timeoutSeconds - Maximum time to wait up to in seconds.
      Returns:
      StatusCode of the set command
    • clearStickyFaults

      Deprecated, for removal: This API element is subject to removal in a future version.
      Clear the sticky faults in the device.

      This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.

      This will wait up to 0.050 seconds (50ms) by default.

      Returns:
      StatusCode of the set command