Class CANifier

java.lang.Object
com.ctre.phoenix.CANifier

public class CANifier
extends Object
CTRE CANifier Device for interfacing common devices to the CAN bus.
  • Field Details

  • Constructor Details

    • CANifier

      public CANifier​(int deviceId)
      Constructor.
      Parameters:
      deviceId - The CAN Device ID of the CANifier.
  • Method Details

    • DestroyObject

      Destructor
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setLEDOutput

      public void setLEDOutput​(double percentOutput, CANifier.LEDChannel ledChannel)
      Sets the LED Output
      Parameters:
      percentOutput - Output duty cycle expressed as percentage.
      ledChannel - Channel to set the output of.
    • setGeneralOutput

      public void setGeneralOutput​(CANifier.GeneralPin outputPin, boolean outputValue, boolean outputEnable)
      Sets the output of a General Pin
      Parameters:
      outputPin - The pin to use as output.
      outputValue - The desired output state.
      outputEnable - Whether this pin is an output. "True" enables output.
    • setGeneralOutputs

      public void setGeneralOutputs​(int outputBits, int isOutputBits)
      Sets the output of all General Pins
      Parameters:
      outputBits - A bit mask of all the output states. LSB->MSB is in the order of the com.ctre.phoenix.CANifier.GeneralPin enum.
      isOutputBits - A boolean bit mask that sets the pins to be outputs or inputs. A bit of 1 enables output.
    • getGeneralInputs

      public void getGeneralInputs​(CANifier.PinValues allPins)
      Gets the state of all General Pins
      Parameters:
      allPins - A structure to fill with the current state of all pins.
    • getGeneralInput

      public boolean getGeneralInput​(CANifier.GeneralPin inputPin)
      Gets the state of the specified pin
      Parameters:
      inputPin - The index of the pin.
      Returns:
      The state of the pin.
    • 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.
    • setPWMOutput

      public void setPWMOutput​(int pwmChannel, double dutyCycle)
      Sets the PWM Output Currently supports PWM 0, PWM 1, and PWM 2
      Parameters:
      pwmChannel - Index of the PWM channel to output.
      dutyCycle - Duty Cycle (0 to 1) to output. Default period of the signal is 4.2 ms.
    • enablePWMOutput

      public void enablePWMOutput​(int pwmChannel, boolean bEnable)
      Enables PWM Outputs Currently supports PWM 0, PWM 1, and PWM 2
      Parameters:
      pwmChannel - Index of the PWM channel to enable.
      bEnable - "True" enables output on the pwm channel.
    • getPWMInput

      public void getPWMInput​(CANifier.PWMChannel pwmChannel, double[] pulseWidthAndPeriod)
      Gets the PWM Input
      Parameters:
      pwmChannel - PWM channel to get.
      pulseWidthAndPeriod - Double array to hold Duty Cycle [0] and Period [1].
    • getQuadraturePosition

      public int getQuadraturePosition()
      Gets the quadrature encoder's position
      Returns:
      Position of encoder
    • setQuadraturePosition

      public ErrorCode setQuadraturePosition​(int newPosition, int timeoutMs)
      Sets the quadrature encoder's position
      Parameters:
      newPosition - Position to set
      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.
    • getQuadratureVelocity

      public int getQuadratureVelocity()
      Gets the quadrature encoder's velocity
      Returns:
      Velocity of encoder
    • configVelocityMeasurementPeriod

      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
      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.
    • configVelocityMeasurementPeriod

      Deprecated.
      Use the overload with SensorVelocityMeasPeriod instead.
      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.VelocityMeasPeriod
      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.
    • configVelocityMeasurementPeriod

      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.sensor.SensorVelocityMeasPeriod
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementPeriod

      Deprecated.
      Use the overload with SensorVelocityMeasPeriod instead.
      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementWindow

      public ErrorCode configVelocityMeasurementWindow​(int windowSize, int timeoutMs)
      Sets the number of velocity samples used in the rolling average velocity measurement.
      Parameters:
      windowSize - Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.
      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.
    • configVelocityMeasurementWindow

      public ErrorCode configVelocityMeasurementWindow​(int windowSize)
      Sets the number of velocity samples used in the rolling average velocity measurement.
      Parameters:
      windowSize - Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configClearPositionOnLimitF

      public ErrorCode configClearPositionOnLimitF​(boolean clearPositionOnLimitF, int timeoutMs)
      Enables clearing the position of the feedback sensor when the forward limit switch is triggered
      Parameters:
      clearPositionOnLimitF - Whether clearing is enabled, defaults false
      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.
    • configClearPositionOnLimitR

      public ErrorCode configClearPositionOnLimitR​(boolean clearPositionOnLimitR, int timeoutMs)
      Enables clearing the position of the feedback sensor when the reverse limit switch is triggered
      Parameters:
      clearPositionOnLimitR - Whether clearing is enabled, defaults false
      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.
    • configClearPositionOnQuadIdx

      public ErrorCode configClearPositionOnQuadIdx​(boolean clearPositionOnQuadIdx, int timeoutMs)
      Enables clearing the position of the feedback sensor when the quadrature index signal is detected
      Parameters:
      clearPositionOnQuadIdx - Whether clearing is enabled, defaults false
      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, int timeoutMs)
      Sets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/duty cycle/output 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/duty cycle/output 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 timeoutMs)
      Gets the value of a custom parameter. This is for arbitrary use. Sometimes it is necessary to save calibration/duty cycle/output 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]
      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 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/duty cycle/output 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.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(CANifierStatusFrame 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​(CANifierStatusFrame 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​(CANifierStatusFrame 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​(CANifierControlFrame 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.
    • getFirmwareVersion

      public int getFirmwareVersion()
      Gets the firmware version of the device.
      Returns:
      Firmware version of device.
    • hasResetOccurred

      public boolean hasResetOccurred()
      Returns true if the device has reset since last call.
      Returns:
      Has a Device Reset Occurred?
    • getFaults

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

      Gets the CANifier sticky fault status
      Parameters:
      toFill - Container for sticky fault statuses.
      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.
    • getBusVoltage

      public double getBusVoltage()
      Gets the bus voltage seen by the device.
      Returns:
      The bus voltage value (in volts).
    • getDeviceID

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

      public ErrorCode configAllSettings​(CANifierConfiguration 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​(CANifierConfiguration 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​(CANifierConfiguration 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.