Class CANCoder

java.lang.Object
com.ctre.phoenix.sensors.CANCoder
Direct Known Subclasses:
WPI_CANCoder

public class CANCoder extends Object
CTRE CANCoder.
 
 // Example usage of a CANCoder
 CANCoder cancoder = new CANCoder(0); // creates a new CANCoder with ID 0

 CANCoderConfiguration config = new CANCoderConfiguration();
 // set units of the CANCoder to radians, with velocity being radians per second
 config.sensorCoefficient = 2 * Math.PI / 4096.0;
 config.unitString = "rad";
 config.sensorTimeBase = SensorTimeBase.PerSecond;
 cancoder.configAllSettings(config);

 System.out.println(cancoder.getPosition()); // prints the position of the CANCoder
 System.out.println(cancoder.getVelocity()); // prints the velocity recorded by the CANCoder

 ErrorCode error = cancoder.getLastError(); // gets the last error generated by the CANCoder
 CANCoderFaults faults = new CANCoderFaults();
 ErrorCode faultsError = cancoder.getFaults(faults); // fills faults with the current CANCoder faults; returns the last error generated

 cancoder.setStatusFramePeriod(CANCoderStatusFrame.SensorData, 10); // changes the period of the sensor data frame to 10ms
 
 
  • Constructor Details

    • CANCoder

      public CANCoder(int deviceNumber, String canbus)
      Constructor.
      Parameters:
      deviceNumber - The CAN Device ID of the CANCoder.
      canbus - Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
    • CANCoder

      public CANCoder(int deviceNumber)
      Constructor.
      Parameters:
      deviceNumber - The CAN Device ID of the CANCoder.
  • Method Details

    • DestroyObject

    • getDeviceID

      public int getDeviceID()
    • getSimCollection

      Returns:
      object that can set simulation inputs.
    • getPosition

      public double getPosition()
      Gets the position of the sensor. This may be relative or absolute depending on configuration. The units are determined by the coefficient and unit-string configuration params, default is degrees.
      Returns:
      The position of the sensor.
    • setPosition

      public ErrorCode setPosition(double newPosition, int timeoutMs)
      Sets the position of the sensor. The units are determined by the coefficient and unit-string configuration params, default is degrees.
      Parameters:
      newPosition -
      Returns:
      ErrorCode generated by function. 0 indicates no error.
    • setPosition

      public ErrorCode setPosition(double newPosition)
      Sets the position of the sensor. The units are determined by the coefficient and unit-string configuration params, default is degrees.
      Parameters:
      newPosition -
      Returns:
      ErrorCode generated by function. 0 indicates no error.
    • setPositionToAbsolute

      public ErrorCode setPositionToAbsolute(int timeoutMs)
      Sets the position of the sensor to match the magnet's "Absolute Sensor". The units are determined by the coefficient and unit-string configuration params, default is degrees.
      Returns:
      ErrorCode generated by function. 0 indicates no error.
    • setPositionToAbsolute

      Sets the position of the sensor to match the magnet's "Absolute Sensor". The units are determined by the coefficient and unit-string configuration params, default is degrees.
      Returns:
      ErrorCode generated by function. 0 indicates no error.
    • getVelocity

      public double getVelocity()
      Gets the velocity of the sensor. The units are determined by the coefficient and unit-string configuration params, default is degrees per second.
      Returns:
      The Velocity of the sensor.
    • getAbsolutePosition

      public double getAbsolutePosition()
      Gets the absolute position of the sensor. The absolute position may be unsigned (for example: [0,360) deg), or signed (for example: [-180,+180) deg). This is determined by a configuration. The default selection is unsigned. The units are determined by the coefficient and unit-string configuration params, default is degrees. Note: this signal is not affected by calls to SetPosition().
      Returns:
      The position of the sensor.
    • 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.
      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.
      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.
    • configAbsoluteSensorRange

      public ErrorCode configAbsoluteSensorRange(AbsoluteSensorRange absoluteSensorRange, int timeoutMs)
      Sets the signage and range of the "Absolute Position" signal. Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...
      Parameters:
      absoluteSensorRange - Desired Sign/Range for the absolute position 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.
    • configAbsoluteSensorRange

      Sets the signage and range of the "Absolute Position" signal. Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...
      Parameters:
      absoluteSensorRange - Desired Sign/Range for the absolute position register.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configMagnetOffset

      public ErrorCode configMagnetOffset(double offsetDegrees, int timeoutMs)
      Adjusts the zero point for the absolute position register. The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) and a hard-limited mechanism may have such a discontinuity in its functional range. In which case use this config to move the discontinuity outside of the function range.
      Parameters:
      offsetDegrees - Offset in degrees (unit string and coefficient DO NOT apply for this config).
      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.
    • configMagnetOffset

      public ErrorCode configMagnetOffset(double offsetDegrees)
      Adjusts the zero point for the absolute position register. The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) and a hard-limited mechanism may have such a discontinuity in its functional range. In which case use this config to move the discontinuity outside of the function range.
      Parameters:
      offsetDegrees - Offset in degrees (unit string and coefficient DO NOT apply for this config).
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configSensorInitializationStrategy

      public ErrorCode configSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy, int timeoutMs)
      Pick the strategy on how to initialize the CANCoder's "Position" register. Depending on the mechanism, it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset.
      Parameters:
      initializationStrategy - The sensor initialization strategy to use. This will impact the behavior the next time CANCoder boots up.
      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.
    • configSensorInitializationStrategy

      Pick the strategy on how to initialize the CANCoder's "Position" register. Depending on the mechanism, it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset.
      Parameters:
      initializationStrategy - The sensor initialization strategy to use. This will impact the behavior the next time CANCoder boots up.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configFeedbackCoefficient

      public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase, int timeoutMs)
      Choose what units you want the API to get/set. This also impacts the units displayed in Self-Test in Tuner. Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters).
      Parameters:
      sensorCoefficient - Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees.
      unitString - String holding the unit to report in. This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner. The string value itself is arbitrary. The max number of letters will depend on firmware versioning, but generally CANCoder supports up to eight letters. However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit. Default is "deg"
      sensorTimeBase - Desired denominator to report velocity in. This impacts GetVelocity and the reported velocity in self-test in Tuner. Default is "Per Second".
      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.
    • configFeedbackCoefficient

      public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase)
      Choose what units you want the API to get/set. This also impacts the units displayed in Self-Test in Tuner. Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters).
      Parameters:
      sensorCoefficient - Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees.
      unitString - String holding the unit to report in. This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner. The string value itself is arbitrary. The max number of letters will depend on firmware versioning, but generally CANCoder supports up to eight letters. However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit. Default is "deg"
      sensorTimeBase - Desired denominator to report velocity in. This impacts GetVelocity and the reported velocity in self-test in Tuner. Default is "Per Second".
      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).
    • getMagnetFieldStrength

      Gets the magnet's health.
      Returns:
      The magnet health code (red/orange/green).
    • configSensorDirection

      public ErrorCode configSensorDirection(boolean bSensorDirection, int timeoutMs)
      Choose which direction is interpreted as positive displacement. This affects both "Position" and "Absolute Position".
      Parameters:
      bSensorDirection - False (default) means positive rotation occurs when magnet is spun counter-clockwise when observer is facing the LED side of CANCoder.
      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.
    • configSensorDirection

      public ErrorCode configSensorDirection(boolean bSensorDirection)
      Choose which direction is interpreted as positive displacement. This affects both "Position" and "Absolute Position".
      Parameters:
      bSensorDirection - False (default) means positive rotation occurs when magnet is spun counter-clockwise when observer is facing the LED side of CANCoder.
      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.
    • getLastUnitString

      Get the units for the signal retrieved in the last called get routine.
    • getLastTimestamp

      public double getLastTimestamp()
      Get the timestamp of the CAN frame retrieved in the last called get routine.
    • 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.
    • 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(CANCoderStatusFrame 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(CANCoderStatusFrame 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(CANCoderStatusFrame 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.
    • 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

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

      Gets the CANCoder 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
      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.
    • configGetVelocityMeasurementPeriod

      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetVelocityMeasurementPeriod

      Returns:
      Read value of the config param.
    • configGetVelocityMeasurementWindow

      public int configGetVelocityMeasurementWindow(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetVelocityMeasurementWindow

      Returns:
      Read value of the config param.
    • configGetAbsoluteSensorRange

      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetAbsoluteSensorRange

      Returns:
      Read value of the config param.
    • configGetMagnetOffset

      public double configGetMagnetOffset(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetMagnetOffset

      public double configGetMagnetOffset()
      Returns:
      Read value of the config param.
    • configGetSensorDirection

      public boolean configGetSensorDirection(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetSensorDirection

      public boolean configGetSensorDirection()
      Returns:
      Read value of the config param.
    • configGetSensorInitializationStrategy

      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetSensorInitializationStrategy

      Returns:
      Read value of the config param.
    • configGetFeedbackCoefficient

      public double configGetFeedbackCoefficient(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetFeedbackCoefficient

      Returns:
      Read value of the config param.
    • configGetFeedbackUnitString

      public String configGetFeedbackUnitString(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetFeedbackUnitString

      Returns:
      Read value of the config param.
    • configGetFeedbackTimeBase

      public SensorTimeBase configGetFeedbackTimeBase(int timeoutMs)
      Parameters:
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.
      Returns:
      Read value of the config param.
    • configGetFeedbackTimeBase

      Returns:
      Read value of the config param.
    • configAllSettings

      public ErrorCode configAllSettings(CANCoderConfiguration 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(CANCoderConfiguration 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(CANCoderConfiguration 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.
      Returns:
      Error Code generated by function. 0 indicates no error.