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 class
CANSparkMax.ExternalFollower
static class
CANSparkMax.FaultID
static class
CANSparkMax.IdleMode
static class
CANSparkMax.InputMode
static class
CANSparkMax.SensorType
-
Nested classes/interfaces inherited from class com.revrobotics.CANSparkMaxLowLevel
CANSparkMaxLowLevel.ConfigParameter, CANSparkMaxLowLevel.FollowConfig, CANSparkMaxLowLevel.MotorType, CANSparkMaxLowLevel.ParameterStatus, CANSparkMaxLowLevel.ParameterType, CANSparkMaxLowLevel.PeriodicFrame, CANSparkMaxLowLevel.PeriodicStatus0, CANSparkMaxLowLevel.PeriodicStatus1, CANSparkMaxLowLevel.PeriodicStatus2
-
-
Field Summary
-
Fields inherited from class com.revrobotics.CANSparkMaxLowLevel
kDefaultCANTimeoutMs, kDefaultControlFramePeriodMs, kDefaultStatus0PeriodMs, kDefaultStatus1PeriodMs, kDefaultStatus2PeriodMs, kMinFirmwareVersion, kNumFirmwareRetries, m_can, m_canTimeoutMs, m_controlPeriodMs, m_inverted
-
-
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 CANError
burnFlash()
Writes all settings to flash.CANError
clearFaults()
Clears all non-sticky faults.void
close()
Closes the SPARK MAX Controllervoid
disable()
Common interface for disabling a motor.CANError
follow(CANSparkMax leader)
Causes this controller's output to mirror the provided leader.CANError
follow(CANSparkMax.ExternalFollower leader, int deviceID)
Causes this controller's output to mirror the provided leader.CANError
follow(CANSparkMax.ExternalFollower leader, int deviceID, boolean invert)
Causes this controller's output to mirror the provided leader.CANError
follow(CANSparkMax leader, boolean invert)
Causes this controller's output to mirror the provided leader.double
get()
Common interface for getting the current set speed of a speed controller.double
getAppliedOutput()
Returns motor controller's output voltage.double
getBusVoltage()
Returns the voltage fed into the motor controller.CANEncoder
getEncoder()
Returns and object for interfacing with the integrated encoder.boolean
getFault(CANSparkMax.FaultID faultID)
Returns whether the fault with the given ID occurred.short
getFaults()
Returns fault bits.CANDigitalInput
getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Returns an object for interfacing with the integrated forward limit switch.CANSparkMax.IdleMode
getIdleMode()
Gets the idle mode setting for the SPARK MAX.boolean
getInverted()
Common interface for returning the inversion state of a speed controller.double
getMotorTemperature()
Returns the motor temperature in Celsius.double
getOutputCurrent()
Returns motor controller's output current in Amps.CANPIDController
getPIDController()
Returns an object for interfacing with the integrated PID controller.double
getRampRate()
Get the configured ramp rate This is the maximum rate at which the motor controller's output is allowed to change.CANDigitalInput
getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Returns an object for interfacing with the integrated reverse limit switch.boolean
getStickyFault(CANSparkMax.FaultID faultID)
Returns whether the sticky fault with the given ID occurred.short
getStickyFaults()
Returns sticky fault bits.boolean
isFollower()
Returns whether the controller is following another controllervoid
pidWrite(double output)
void
set(double speed)
Common interface for setting the speed of a speed controller.CANError
setCANTimeout(int milliseconds)
Sets timeout for sending CAN messages.CANError
setIdleMode(CANSparkMax.IdleMode mode)
Sets the idle mode setting for the SPARK MAX.void
setInverted(boolean isInverted)
Common interface for inverting direction of a speed controller.CANError
setRampRate(double rate)
Sets the ramp rate for all control modes.CANError
setSecondaryCurrentLimit(double limit)
Sets the secondary current limit in Amps.CANError
setSecondaryCurrentLimit(double limit, int chopCycles)
Sets the secondary current limit in Amps.CANError
setSmartCurrentLimit(int limit)
Sets the current limit in Amps.CANError
setSmartCurrentLimit(int stallLimit, int freeLimit)
Sets the current limit in Amps.CANError
setSmartCurrentLimit(int stallLimit, int freeLimit, int limitRPM)
Sets the current limit in Amps.void
stopMotor()
-
Methods inherited from class com.revrobotics.CANSparkMaxLowLevel
getControlFramePeriod, getDeviceId, getFirmwareString, getFirmwareVersion, getMotorType, getParameterBoolean, getParameterCore, getParameterDouble, getParameterInt, getParameterType, getPeriodicStatus0, getPeriodicStatus1, getPeriodicStatus2, getSerialNumber, setControlFramePeriod, setMotorType, setParameter, setParameter, setParameter, setParameterCore, 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:
close
in interfacejava.lang.AutoCloseable
-
set
public void set(double speed)
Common interface for setting the speed of a speed controller.- Specified by:
set
in interfaceedu.wpi.first.wpilibj.SpeedController
- Parameters:
speed
- The speed to set. Value should be between -1.0 and 1.0.
-
get
public double get()
Common interface for getting the current set speed of a speed controller.- Specified by:
get
in 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.- Specified by:
setInverted
in 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.- Specified by:
getInverted
in 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:
disable
in interfaceedu.wpi.first.wpilibj.SpeedController
-
stopMotor
public void stopMotor()
- Specified by:
stopMotor
in interfaceedu.wpi.first.wpilibj.SpeedController
-
pidWrite
public void pidWrite(double output)
- Specified by:
pidWrite
in interfaceedu.wpi.first.wpilibj.PIDOutput
-
getEncoder
public CANEncoder getEncoder()
Returns and object for interfacing with the integrated encoder.
-
getPIDController
public CANPIDController getPIDController()
Returns an object for interfacing with the integrated PID controller.
-
getForwardLimitSwitch
public CANDigitalInput getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Returns an object for interfacing with the integrated forward limit switch.- Parameters:
polarity
- Whether the limit switch is normally open or normally closed.
-
getReverseLimitSwitch
public CANDigitalInput getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Returns an object for interfacing with the integrated reverse limit switch.- Parameters:
polarity
- Whether the limit switch is normally open or normally closed.
-
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.
-
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).
-
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
-
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.
-
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.
-
setIdleMode
public CANError setIdleMode(CANSparkMax.IdleMode mode)
Sets the idle mode setting for the SPARK MAX.- Parameters:
mode
- Idle mode (coast or brake).
-
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
-
setRampRate
public CANError setRampRate(double rate)
Sets the ramp rate for all 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.
-
getRampRate
public double getRampRate()
Get the configured ramp rate This is the maximum rate at which the motor controller's output is allowed to change.- Returns:
- rampte 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.- Parameters:
leader
- The motor controller to follow.
-
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.- Parameters:
leader
- The motor controller to follow.invert
- Set the follower to output opposite of the leader
-
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.- Parameters:
leader
- The type of motor controller to follow (Talon SRX, Spark Max, etc.).deviceID
- The CAN ID of the device to follow.
-
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.- 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
-
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 fault bits.
-
getStickyFaults
public short getStickyFaults()
Returns sticky fault bits.
-
getFault
public boolean getFault(CANSparkMax.FaultID faultID)
Returns whether the fault with the given ID occurred.
-
getStickyFault
public boolean getStickyFault(CANSparkMax.FaultID faultID)
Returns whether 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 motor controller's output voltage.
-
getOutputCurrent
public double getOutputCurrent()
Returns motor controller's output current in Amps.
-
getMotorTemperature
public double getMotorTemperature()
Returns the motor temperature in Celsius.
-
clearFaults
public CANError clearFaults()
Clears all non-sticky faults. Sticky faults must be cleared by resetting the motor controller.
-
burnFlash
public CANError burnFlash()
Writes all settings to flash.
-
setCANTimeout
public CANError setCANTimeout(int milliseconds)
Sets timeout for sending CAN messages.- Parameters:
milliseconds
- The timeout in milliseconds.
-
-