Package com.revrobotics
Class CANSparkMax
- java.lang.Object
-
- com.revrobotics.CANSparkMaxLowLevel
-
- com.revrobotics.CANSparkMax
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.PIDOutput,edu.wpi.first.wpilibj.SpeedController,java.lang.AutoCloseable
public class CANSparkMax extends CANSparkMaxLowLevel implements java.lang.AutoCloseable
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static classCANSparkMax.ExternalFollowerstatic classCANSparkMax.FaultIDstatic classCANSparkMax.IdleModestatic classCANSparkMax.InputModestatic classCANSparkMax.SoftLimitDirection-
Nested classes/interfaces inherited from class com.revrobotics.CANSparkMaxLowLevel
CANSparkMaxLowLevel.FollowConfig, CANSparkMaxLowLevel.MotorType, CANSparkMaxLowLevel.PeriodicFrame, CANSparkMaxLowLevel.PeriodicStatus0, CANSparkMaxLowLevel.PeriodicStatus1, CANSparkMaxLowLevel.PeriodicStatus2
-
-
Field Summary
-
Fields inherited from class com.revrobotics.CANSparkMaxLowLevel
kAPIBuildVersion, kAPIMajorVersion, kAPIMinorVersion, kAPIVersion, m_motorType, m_sparkMax
-
-
Constructor Summary
Constructors Constructor Description CANSparkMax(int deviceID, CANSparkMaxLowLevel.MotorType type)Create a new SPARK MAX Controller
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description CANErrorburnFlash()Writes all settings to flash.CANErrorclearFaults()Clears all sticky faults.voidclose()Closes the SPARK MAX Controllervoiddisable()Common interface for disabling a motor.CANErrordisableVoltageCompensation()Disables the voltage compensation setting for all modes on the SPARK MAX.CANErrorenableSoftLimit(CANSparkMax.SoftLimitDirection direction, boolean enable)Enable soft limitsCANErrorenableVoltageCompensation(double nominalVoltage)Sets the voltage compensation setting for all modes on the SPARK MAX and enables voltage compensation.CANErrorfollow(CANSparkMax leader)Causes this controller's output to mirror the provided leader.CANErrorfollow(CANSparkMax.ExternalFollower leader, int deviceID)Causes this controller's output to mirror the provided leader.CANErrorfollow(CANSparkMax.ExternalFollower leader, int deviceID, boolean invert)Causes this controller's output to mirror the provided leader.CANErrorfollow(CANSparkMax leader, boolean invert)Causes this controller's output to mirror the provided leader.doubleget()Common interface for getting the current set speed of a speed controller.CANEncodergetAlternateEncoder()Returns an object for interfacing with an encoder connected to the alternate data port configured pins.CANEncodergetAlternateEncoder(AlternateEncoderType sensorType, int counts_per_rev)Returns an object for interfacing with an encoder connected to the alternate data port configured pins.CANAnaloggetAnalog(CANAnalog.AnalogMode mode)doublegetAppliedOutput()doublegetBusVoltage()doublegetClosedLoopRampRate()Get the configured closed loop ramp rate This is the maximum rate at which the motor controller's output is allowed to change.CANEncodergetEncoder()Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.CANEncodergetEncoder(EncoderType sensorType, int counts_per_rev)Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX.booleangetFault(CANSparkMax.FaultID faultID)Get the value of a specific faultshortgetFaults()protected intgetFeedbackDeviceID()Gets the feedback device ID that was set on SparkMax itself.CANDigitalInputgetForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)CANSparkMax.IdleModegetIdleMode()Gets the idle mode setting for the SPARK MAX.booleangetInverted()Common interface for returning the inversion state of a speed controller.CANErrorgetLastError()All device errors are tracked on a per thread basis for all devices in that thread.doublegetMotorTemperature()doublegetOpenLoopRampRate()Get the configured open loop ramp rate This is the maximum rate at which the motor controller's output is allowed to change.doublegetOutputCurrent()CANPIDControllergetPIDController()CANDigitalInputgetReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)doublegetSoftLimit(CANSparkMax.SoftLimitDirection direction)Get the soft limit setting in the controllerbooleangetStickyFault(CANSparkMax.FaultID faultID)Get the value of a specific sticky faultshortgetStickyFaults()doublegetVoltageCompensationNominalVoltage()Get the configured voltage compensation nominal voltage valuebooleanisFollower()Returns whether the controller is following another controllerbooleanisSoftLimitEnabled(CANSparkMax.SoftLimitDirection direction)voidpidWrite(double output)voidset(double speed)Common interface for setting the speed of a speed controller.CANErrorsetCANTimeout(int milliseconds)Sets timeout for sending CAN messages with SetParameter* and GetParameter* calls.CANErrorsetClosedLoopRampRate(double rate)Sets the ramp rate for closed loop control modes.CANErrorsetIdleMode(CANSparkMax.IdleMode mode)Sets the idle mode setting for the SPARK MAX.voidsetInverted(boolean isInverted)Common interface for inverting direction of a speed controller.CANErrorsetOpenLoopRampRate(double rate)Sets the ramp rate for open loop control modes.CANErrorsetSecondaryCurrentLimit(double limit)Sets the secondary current limit in Amps.CANErrorsetSecondaryCurrentLimit(double limit, int chopCycles)Sets the secondary current limit in Amps.CANErrorsetSmartCurrentLimit(int limit)Sets the current limit in Amps.CANErrorsetSmartCurrentLimit(int stallLimit, int freeLimit)Sets the current limit in Amps.CANErrorsetSmartCurrentLimit(int stallLimit, int freeLimit, int limitRPM)Sets the current limit in Amps.CANErrorsetSoftLimit(CANSparkMax.SoftLimitDirection direction, float limit)Set the soft limit based on position.voidsetVoltage(double outputVolts)Sets the voltage output of the SpeedController.voidstopMotor()-
Methods inherited from class com.revrobotics.CANSparkMaxLowLevel
enableExternalUSBControl, getDeviceId, getFirmwareString, getFirmwareVersion, getInitialMotorType, getMotorType, getSafeFloat, getSerialNumber, restoreFactoryDefaults, restoreFactoryDefaults, setAltEncPosition, setControlFramePeriodMs, setEncPosition, setIAccum, setMotorType, setPeriodicFramePeriod
-
-
-
-
Constructor Detail
-
CANSparkMax
public CANSparkMax(int deviceID, CANSparkMaxLowLevel.MotorType type)Create a new SPARK MAX Controller- Parameters:
deviceID- The device ID.type- The motor type connected to the controller. Brushless motors must be connected to their matching color and the hall sensor plugged in. Brushed motors must be connected to the Red and Black terminals only.
-
-
Method Detail
-
close
public void close()
Closes the SPARK MAX Controller- Specified by:
closein interfacejava.lang.AutoCloseable
-
set
public void set(double speed)
Common interface for setting the speed of a speed controller.- Specified by:
setin interfaceedu.wpi.first.wpilibj.SpeedController- 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.- Specified by:
setVoltagein interfaceedu.wpi.first.wpilibj.SpeedController- Parameters:
outputVolts- The voltage to output.
-
get
public double get()
Common interface for getting the current set speed of a speed controller.- Specified by:
getin interfaceedu.wpi.first.wpilibj.SpeedController- 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.- Specified by:
setInvertedin interfaceedu.wpi.first.wpilibj.SpeedController- 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.- Specified by:
getInvertedin interfaceedu.wpi.first.wpilibj.SpeedController- Returns:
- isInverted The state of inversion, true is inverted.
-
disable
public void disable()
Common interface for disabling a motor.- Specified by:
disablein interfaceedu.wpi.first.wpilibj.SpeedController
-
stopMotor
public void stopMotor()
- Specified by:
stopMotorin interfaceedu.wpi.first.wpilibj.SpeedController
-
pidWrite
public void pidWrite(double output)
- Specified by:
pidWritein interfaceedu.wpi.first.wpilibj.PIDOutput
-
getEncoder
public CANEncoder getEncoder()
Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX. The default encoder type is assumed to be the hall effect for brushless. This can be modified for brushed DC to use a quadrature encoder. Assumes that the encoder the is integrated encoder, configured as: EncoderType.kHallEffect, 0 counts per revolution.- Returns:
- An object for interfacing with the integrated encoder.
-
getEncoder
public CANEncoder getEncoder(EncoderType sensorType, int counts_per_rev)
Returns and object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX. The default encoder type is assumed to be the hall effect for brushless. This can be modified for brushed DC to use a quadrature encoder.- Parameters:
sensorType- The encoder type for the motor: kHallEffect or kQuadraturecounts_per_rev- The counts per revolution of the encoder- Returns:
- An object for interfacing with an encoder
-
getAlternateEncoder
public CANEncoder getAlternateEncoder()
Returns an object for interfacing with an encoder connected to the alternate data port configured pins. This is defined as : Mutli-function Pin: Encoder A Limit Switch Reverse: Encoder B This call will disable the limit switch inputs- Returns:
- Returns an object for interfacing with an encoder connected to the alternate data port configured pins
-
getAlternateEncoder
public CANEncoder getAlternateEncoder(AlternateEncoderType sensorType, int counts_per_rev)
Returns an object for interfacing with an encoder connected to the alternate data port configured pins. This is defined as : Mutli-function Pin: Encoder A Limit Switch Reverse: Encoder B This call will disable the limit switch inputs.- Parameters:
counts_per_rev- the Counts per revolution of the encodersensorType- The encoder type for the motor: currently only kQuadrature- Returns:
- Returns an object for interfacing with an encoder connected to the alternate data port configured pins
-
getAnalog
public CANAnalog getAnalog(CANAnalog.AnalogMode mode)
- Parameters:
mode- The mode of the analog sensor, either absolute or relative- Returns:
- An object for interfacing with a connected analog sensor.
-
getPIDController
public CANPIDController getPIDController()
- Returns:
- An object for interfacing with the integrated PID controller.
-
getForwardLimitSwitch
public CANDigitalInput getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
- Parameters:
polarity- Whether the limit switch is normally open or normally closed.- Returns:
- An object for interfacing with the integrated forward limit switch.
-
getReverseLimitSwitch
public CANDigitalInput getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
- Parameters:
polarity- Whether the limit switch is normally open or normally closed.- Returns:
- An object for interfacing with the integrated reverse limit switch.
-
setSmartCurrentLimit
public CANError 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:
- CANError Set to CANError.kOK if successful
-
setSmartCurrentLimit
public CANError 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:
- CANError Set to CANError.kOK if successful
-
setSmartCurrentLimit
public CANError 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:
- CANError Set to CANError.kOK if successful
-
setSecondaryCurrentLimit
public CANError 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 equationt = (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:
- CANError Set to CANError.kOK if successful
-
setSecondaryCurrentLimit
public CANError 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 equationt = (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:
- CANError Set to CANError.kOK if successful
-
setIdleMode
public CANError setIdleMode(CANSparkMax.IdleMode mode)
Sets the idle mode setting for the SPARK MAX.- Parameters:
mode- Idle mode (coast or brake).- Returns:
- CANError Set to CANError.kOK if successful
-
getIdleMode
public CANSparkMax.IdleMode 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 CANError 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:
- CANError Set to CANError.kOK if successful
-
disableVoltageCompensation
public CANError disableVoltageCompensation()
Disables the voltage compensation setting for all modes on the SPARK MAX.- Returns:
- CANError Set to CANError.kOK if successful
-
getVoltageCompensationNominalVoltage
public double getVoltageCompensationNominalVoltage()
Get the configured voltage compensation nominal voltage value- Returns:
- The nominal voltage for voltage compensation mode.
-
setOpenLoopRampRate
public CANError 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:
- CANError Set to CANError.kOK if successful
-
setClosedLoopRampRate
public CANError 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:
- CANError Set to CANError.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 CANError 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:
- CANError Set to CANError.kOK if successful
-
follow
public CANError 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:
- CANError Set to CANError.kOK if successful
-
follow
public CANError 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:
- CANError Set to CANError.kOK if successful
-
follow
public CANError 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:
- CANError Set to CANError.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
public CANError clearFaults()
Clears all sticky faults.- Returns:
- CANError Set to CANError.kOK if successful
-
burnFlash
public CANError burnFlash()
Writes all settings to flash.- Returns:
- CANError Set to CANError.kOK if successful
-
setCANTimeout
public CANError 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:
- CANError Set to CANError.kOK if successful
-
enableSoftLimit
public CANError enableSoftLimit(CANSparkMax.SoftLimitDirection direction, boolean enable)
Enable soft limits- Parameters:
direction- the direction of motion to restrictenable- set true to enable soft limits- Returns:
- CANError Set to CANError.kOK if successful
-
setSoftLimit
public CANError 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 restrictlimit- position soft limit of the controller- Returns:
- CANError Set to CANError.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
public boolean isSoftLimitEnabled(CANSparkMax.SoftLimitDirection direction)
- 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
public CANError 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.
-
-