Class CANSparkMax

All Implemented Interfaces:
edu.wpi.first.wpilibj.motorcontrol.MotorController, edu.wpi.first.wpilibj.SpeedController, AutoCloseable

public class CANSparkMax extends CANSparkMaxLowLevel
  • Constructor Details

    • CANSparkMax

      public CANSparkMax(int deviceId, CANSparkMaxLowLevel.MotorType type)
      Create a new object to control a SPARK MAX motor Controller
      Parameters:
      deviceId - The device ID.
      type - The motor type connected to the controller. Brushless motor wires must be connected to their matching colors and the hall sensor must be plugged in. Brushed motors must be connected to the Red and Black terminals only.
  • Method Details

    • set

      public void set(double speed)
      Common interface for setting the speed of a speed controller.
      Parameters:
      speed - The speed to set. Value should be between -1.0 and 1.0.
    • setVoltage

      public void setVoltage(double outputVolts)
      Sets the voltage output of the SpeedController. This is equivillant to a call to SetReference(output, rev::ControlType::kVoltage). The behavior of this call differs slightly from the WPILib documetation for this call since the device internally sets the desired voltage (not a compensation value). That means that this *can* be a 'set-and-forget' call.
      Parameters:
      outputVolts - The voltage to output.
    • get

      public double get()
      Common interface for getting the current set speed of a speed controller.
      Returns:
      The current set speed. Value is between -1.0 and 1.0.
    • setInverted

      public void setInverted(boolean isInverted)
      Common interface for inverting direction of a speed controller.

      This call has no effect if the controller is a follower. To invert a follower, see the follow() method.

      Parameters:
      isInverted - The state of inversion, true is inverted.
    • getInverted

      public boolean getInverted()
      Common interface for returning the inversion state of a speed controller.

      This call has no effect if the controller is a follower.

      Returns:
      isInverted The state of inversion, true is inverted.
    • disable

      public void disable()
      Common interface for disabling a motor.
    • stopMotor

      public void stopMotor()
      Description copied from interface: edu.wpi.first.wpilibj.SpeedController
      Stops motor movement. Motor can be moved again by calling set without having to re-enable the motor.
    • getEncoder

      Returns an object for interfacing with the hall sensor integrated into a brushless motor, which is connected to the front port of the SPARK MAX.

      To access a quadrature encoder connected to the encoder pins or the front port of the SPARK MAX, you must call the version of this method with EncoderType and countsPerRev parameters.

      Returns:
      An object for interfacing with the integrated encoder.
    • getEncoder

      public RelativeEncoder getEncoder(SparkMaxRelativeEncoder.Type encoderType, int countsPerRev)
      Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.
      Parameters:
      encoderType - The encoder type for the motor: kHallEffect or kQuadrature
      countsPerRev - The counts per revolution of the encoder
      Returns:
      An object for interfacing with an encoder
    • getEncoder

      @Deprecated(forRemoval=true) public RelativeEncoder getEncoder(EncoderType encoderType, int countsPerRev)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.
      Parameters:
      encoderType - The encoder type for the motor: kHallEffect or kQuadrature
      countsPerRev - The counts per revolution of the encoder
      Returns:
      An object for interfacing with an encoder
    • getAlternateEncoder

      public RelativeEncoder getAlternateEncoder(int countsPerRev)
      Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:
      • Pin 4 (Forward Limit Switch): Index
      • Pin 6 (Multi-function): Encoder A
      • Pin 8 (Reverse Limit Switch): Encoder B

      This call will disable support for the limit switch inputs.

      Parameters:
      countsPerRev - The counts per revolution of the encoder
      Returns:
      An object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins
    • getAlternateEncoder

      public RelativeEncoder getAlternateEncoder(SparkMaxAlternateEncoder.Type encoderType, int countsPerRev)
      Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:
      • Pin 4 (Forward Limit Switch): Index
      • Pin 6 (Multi-function): Encoder A
      • Pin 8 (Reverse Limit Switch): Encoder B

      This call will disable support for the limit switch inputs.

      Parameters:
      encoderType - The encoder type for the motor: currently only kQuadrature
      countsPerRev - The counts per revolution of the encoder
      Returns:
      An object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins
    • getAlternateEncoder

      @Deprecated(forRemoval=true) public RelativeEncoder getAlternateEncoder(AlternateEncoderType encoderType, int countsPerRev)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:
      • Pin 4 (Forward Limit Switch): Index
      • Pin 6 (Multi-function): Encoder A
      • Pin 8 (Reverse Limit Switch): Encoder B

      This call will disable support for the limit switch inputs.

      Parameters:
      encoderType - The encoder type for the motor: currently only kQuadrature
      countsPerRev - The counts per revolution of the encoder
      Returns:
      An object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins
    • getAnalog

      Parameters:
      mode - The mode of the analog sensor, either absolute or relative
      Returns:
      An object for interfacing with a connected analog sensor.
    • getAnalog

      Deprecated, for removal: This API element is subject to removal in a future version.
    • getPIDController

      Returns:
      An object for interfacing with the integrated PID controller.
    • getForwardLimitSwitch

      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.

      This call will disable support for the alternate encoder.

      Parameters:
      polarity - Whether the limit switch is normally open or normally closed.
      Returns:
      An object for interfacing with the forward limit switch.
    • getForwardLimitSwitch

      Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.

      This call will disable support for the alternate encoder.

      Parameters:
      switchType - Whether the limit switch is normally open or normally closed.
      Returns:
      An object for interfacing with the forward limit switch.
    • getReverseLimitSwitch

      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.

      This call will disable support for the alternate encoder.

      Parameters:
      polarity - Whether the limit switch is normally open or normally closed.
      Returns:
      An object for interfacing with the reverse limit switch.
    • getReverseLimitSwitch

      Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.

      This call will disable support for the alternate encoder.

      Parameters:
      switchType - Whether the limit switch is normally open or normally closed.
      Returns:
      An object for interfacing with the reverse limit switch.
    • setSmartCurrentLimit

      public REVLibError setSmartCurrentLimit(int limit)
      Sets the current limit in Amps.

      The motor controller will reduce the controller voltage output to avoid surpassing this limit. This limit is enabled by default and used for brushless only. This limit is highly recommended when using the NEO brushless motor.

      The NEO Brushless Motor has a low internal resistance, which can mean large current spikes that could be enough to cause damage to the motor and controller. This current limit provides a smarter strategy to deal with high current draws and keep the motor and controller operating in a safe region.

      Parameters:
      limit - The current limit in Amps.
      Returns:
      REVLibError.kOk if successful
    • setSmartCurrentLimit

      public REVLibError setSmartCurrentLimit(int stallLimit, int freeLimit)
      Sets the current limit in Amps.

      The motor controller will reduce the controller voltage output to avoid surpassing this limit. This limit is enabled by default and used for brushless only. This limit is highly recommended when using the NEO brushless motor.

      The NEO Brushless Motor has a low internal resistance, which can mean large current spikes that could be enough to cause damage to the motor and controller. This current limit provides a smarter strategy to deal with high current draws and keep the motor and controller operating in a safe region.

      The controller can also limit the current based on the RPM of the motor in a linear fashion to help with controllability in closed loop control. For a response that is linear the entire RPM range leave limit RPM at 0.

      Parameters:
      stallLimit - The current limit in Amps at 0 RPM.
      freeLimit - The current limit at free speed (5700RPM for NEO).
      Returns:
      REVLibError.kOk if successful
    • setSmartCurrentLimit

      public REVLibError setSmartCurrentLimit(int stallLimit, int freeLimit, int limitRPM)
      Sets the current limit in Amps.

      The motor controller will reduce the controller voltage output to avoid surpassing this limit. This limit is enabled by default and used for brushless only. This limit is highly recommended when using the NEO brushless motor.

      The NEO Brushless Motor has a low internal resistance, which can mean large current spikes that could be enough to cause damage to the motor and controller. This current limit provides a smarter strategy to deal with high current draws and keep the motor and controller operating in a safe region.

      The controller can also limit the current based on the RPM of the motor in a linear fashion to help with controllability in closed loop control. For a response that is linear the entire RPM range leave limit RPM at 0.

      Parameters:
      stallLimit - The current limit in Amps at 0 RPM.
      freeLimit - The current limit at free speed (5700RPM for NEO).
      limitRPM - RPM less than this value will be set to the stallLimit, RPM values greater than limitRPM will scale linearly to freeLimit
      Returns:
      REVLibError.kOk if successful
    • setSecondaryCurrentLimit

      public REVLibError setSecondaryCurrentLimit(double limit)
      Sets the secondary current limit in Amps.

      The motor controller will disable the output of the controller briefly if the current limit is exceeded to reduce the current. This limit is a simplified 'on/off' controller. This limit is enabled by default but is set higher than the default Smart Current Limit.

      The time the controller is off after the current limit is reached is determined by the parameter limitCycles, which is the number of PWM cycles (20kHz). The recommended value is the default of 0 which is the minimum time and is part of a PWM cycle from when the over current is detected. This allows the controller to regulate the current close to the limit value.

      The total time is set by the equation t = (50us - t0) + 50us * limitCycles t = total off time after over current t0 = time from the start of the PWM cycle until over current is detected

      Parameters:
      limit - The current limit in Amps.
      Returns:
      REVLibError.kOk if successful
    • setSecondaryCurrentLimit

      public REVLibError setSecondaryCurrentLimit(double limit, int chopCycles)
      Sets the secondary current limit in Amps.

      The motor controller will disable the output of the controller briefly if the current limit is exceeded to reduce the current. This limit is a simplified 'on/off' controller. This limit is enabled by default but is set higher than the default Smart Current Limit.

      The time the controller is off after the current limit is reached is determined by the parameter limitCycles, which is the number of PWM cycles (20kHz). The recommended value is the default of 0 which is the minimum time and is part of a PWM cycle from when the over current is detected. This allows the controller to regulate the current close to the limit value.

      The total time is set by the equation t = (50us - t0) + 50us * limitCycles t = total off time after over current t0 = time from the start of the PWM cycle until over current is detected

      Parameters:
      limit - The current limit in Amps.
      chopCycles - The number of additional PWM cycles to turn the driver off after overcurrent is detected.
      Returns:
      REVLibError.kOk if successful
    • setIdleMode

      Sets the idle mode setting for the SPARK MAX.
      Parameters:
      mode - Idle mode (coast or brake).
      Returns:
      REVLibError.kOk if successful
    • getIdleMode

      Gets the idle mode setting for the SPARK MAX.

      This uses the Get Parameter API and should be used infrequently. This function uses a non-blocking call and will return a cached value if the parameter is not returned by the timeout. The timeout can be changed by calling SetCANTimeout(int milliseconds)

      Returns:
      IdleMode Idle mode setting
    • enableVoltageCompensation

      public REVLibError enableVoltageCompensation(double nominalVoltage)
      Sets the voltage compensation setting for all modes on the SPARK MAX and enables voltage compensation.
      Parameters:
      nominalVoltage - Nominal voltage to compensate output to
      Returns:
      REVLibError.kOk if successful
    • disableVoltageCompensation

      Disables the voltage compensation setting for all modes on the SPARK MAX.
      Returns:
      REVLibError.kOk if successful
    • getVoltageCompensationNominalVoltage

      Get the configured voltage compensation nominal voltage value
      Returns:
      The nominal voltage for voltage compensation mode.
    • setOpenLoopRampRate

      public REVLibError setOpenLoopRampRate(double rate)
      Sets the ramp rate for open loop control modes.

      This is the maximum rate at which the motor controller's output is allowed to change.

      Parameters:
      rate - Time in seconds to go from 0 to full throttle.
      Returns:
      REVLibError.kOk if successful
    • setClosedLoopRampRate

      public REVLibError setClosedLoopRampRate(double rate)
      Sets the ramp rate for closed loop control modes.

      This is the maximum rate at which the motor controller's output is allowed to change.

      Parameters:
      rate - Time in seconds to go from 0 to full throttle.
      Returns:
      REVLibError.kOk if successful
    • getOpenLoopRampRate

      public double getOpenLoopRampRate()
      Get the configured open loop ramp rate

      This is the maximum rate at which the motor controller's output is allowed to change.

      Returns:
      ramp rate time in seconds to go from 0 to full throttle.
    • getClosedLoopRampRate

      public double getClosedLoopRampRate()
      Get the configured closed loop ramp rate

      This is the maximum rate at which the motor controller's output is allowed to change.

      Returns:
      ramp rate time in seconds to go from 0 to full throttle.
    • follow

      public REVLibError follow(CANSparkMax leader)
      Causes this controller's output to mirror the provided leader.

      Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

      The motor will spin in the same direction as the leader. This can be changed by passing a true constant after the leader parameter.

      Following anything other than a CAN SPARK MAX is not officially supported.

      Parameters:
      leader - The motor controller to follow.
      Returns:
      REVLibError.kOk if successful
    • follow

      public REVLibError follow(CANSparkMax leader, boolean invert)
      Causes this controller's output to mirror the provided leader.

      Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

      Following anything other than a CAN SPARK MAX is not officially supported.

      Parameters:
      leader - The motor controller to follow.
      invert - Set the follower to output opposite of the leader
      Returns:
      REVLibError.kOk if successful
    • follow

      public REVLibError follow(CANSparkMax.ExternalFollower leader, int deviceID)
      Causes this controller's output to mirror the provided leader.

      Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

      The motor will spin in the same direction as the leader. This can be changed by passing a true constant after the deviceID parameter.

      Following anything other than a CAN SPARK MAX is not officially supported.

      Parameters:
      leader - The type of motor controller to follow (Talon SRX, SPARK MAX, etc.).
      deviceID - The CAN ID of the device to follow.
      Returns:
      REVLibError.kOk if successful
    • follow

      public REVLibError follow(CANSparkMax.ExternalFollower leader, int deviceID, boolean invert)
      Causes this controller's output to mirror the provided leader.

      Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

      Following anything other than a CAN SPARK MAX is not officially supported.

      Parameters:
      leader - The type of motor controller to follow (Talon SRX, SPARK MAX, etc.).
      deviceID - The CAN ID of the device to follow.
      invert - Set the follower to output opposite of the leader
      Returns:
      REVLibError.kOk if successful
    • isFollower

      public boolean isFollower()
      Returns whether the controller is following another controller
      Returns:
      True if this device is following another controller false otherwise
    • getFaults

      public short getFaults()
      Returns:
      All fault bits as a short
    • getStickyFaults

      public short getStickyFaults()
      Returns:
      All sticky fault bits as a short
    • getFault

      public boolean getFault(CANSparkMax.FaultID faultID)
      Get the value of a specific fault
      Parameters:
      faultID - The ID of the fault to retrive
      Returns:
      True if the fault with the given ID occurred.
    • getStickyFault

      public boolean getStickyFault(CANSparkMax.FaultID faultID)
      Get the value of a specific sticky fault
      Parameters:
      faultID - The ID of the sticky fault to retrive
      Returns:
      True if the sticky fault with the given ID occurred.
    • getBusVoltage

      public double getBusVoltage()
      Returns:
      The voltage fed into the motor controller.
    • getAppliedOutput

      public double getAppliedOutput()
      Returns:
      The motor controller's applied output duty cycle.
    • getOutputCurrent

      public double getOutputCurrent()
      Returns:
      The motor controller's output current in Amps.
    • getMotorTemperature

      public double getMotorTemperature()
      Returns:
      The motor temperature in Celsius.
    • clearFaults

      Clears all sticky faults.
      Returns:
      REVLibError.kOk if successful
    • burnFlash

      Writes all settings to flash.
      Returns:
      REVLibError.kOk if successful
    • setCANTimeout

      public REVLibError setCANTimeout(int milliseconds)
      Sets timeout for sending CAN messages with SetParameter* and GetParameter* calls. These calls will block for up to this amoutn of time before returning a timeout erro. A timeout of 0 will make the SetParameter* calls non-blocking, and instead will check the response in a separate thread. With this configuration, any error messages will appear on the drivestration but will not be returned by the GetLastError() call.
      Parameters:
      milliseconds - The timeout in milliseconds.
      Returns:
      REVLibError.kOk if successful
    • enableSoftLimit

      public REVLibError enableSoftLimit(CANSparkMax.SoftLimitDirection direction, boolean enable)
      Enable soft limits
      Parameters:
      direction - the direction of motion to restrict
      enable - set true to enable soft limits
      Returns:
      REVLibError.kOk if successful
    • setSoftLimit

      public REVLibError setSoftLimit(CANSparkMax.SoftLimitDirection direction, float limit)
      Set the soft limit based on position. The default unit is rotations, but will match the unit scaling set by the user.

      Note that this value is not scaled internally so care must be taken to make sure these units match the desired conversion

      Parameters:
      direction - the direction of motion to restrict
      limit - position soft limit of the controller
      Returns:
      REVLibError.kOk if successful
    • getSoftLimit

      public double getSoftLimit(CANSparkMax.SoftLimitDirection direction)
      Get the soft limit setting in the controller
      Parameters:
      direction - the direction of motion to restrict
      Returns:
      position soft limit setting of the controller
    • isSoftLimitEnabled

      Parameters:
      direction - The direction of the motion to restrict
      Returns:
      true if the soft limit is enabled.
    • getFeedbackDeviceID

      protected int getFeedbackDeviceID()
      Gets the feedback device ID that was set on SparkMax itself.
      Returns:
      Feedback device ID on the SparkMax
    • getLastError

      All device errors are tracked on a per thread basis for all devices in that thread. This is meant to be called immediately following another call that has the possibility of returning an error to validate if an error has occurred.
      Returns:
      the last error that was generated.