Class CANSparkBase
- java.lang.Object
-
- com.revrobotics.CANSparkLowLevel
-
- com.revrobotics.CANSparkBase
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.motorcontrol.MotorController
,java.lang.AutoCloseable
- Direct Known Subclasses:
CANSparkFlex
,CANSparkMax
public abstract class CANSparkBase extends CANSparkLowLevel
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
CANSparkBase.ControlType
static class
CANSparkBase.ExternalFollower
static class
CANSparkBase.FaultID
static class
CANSparkBase.IdleMode
static class
CANSparkBase.InputMode
Deprecated, for removal: This API element is subject to removal in a future version.static class
CANSparkBase.SoftLimitDirection
-
Nested classes/interfaces inherited from class com.revrobotics.CANSparkLowLevel
CANSparkLowLevel.FollowConfig, CANSparkLowLevel.MotorType, CANSparkLowLevel.PeriodicFrame, CANSparkLowLevel.PeriodicStatus0, CANSparkLowLevel.PeriodicStatus1, CANSparkLowLevel.PeriodicStatus2, CANSparkLowLevel.SparkModel
-
-
Field Summary
-
Fields inherited from class com.revrobotics.CANSparkLowLevel
expectedSparkModel, isClosed, kAPIBuildVersion, kAPIMajorVersion, kAPIMinorVersion, kAPIVersion, motorType, sparkMaxHandle
-
-
Constructor Summary
Constructors Constructor Description CANSparkBase(int deviceId, CANSparkLowLevel.MotorType type, CANSparkLowLevel.SparkModel model)
Create a new object to control a SPARK motor Controller
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Deprecated Methods Modifier and Type Method Description REVLibError
burnFlash()
Writes all settings to flash.REVLibError
clearFaults()
Clears all sticky faults.void
disable()
Common interface for disabling a motor.REVLibError
disableVoltageCompensation()
Disables the voltage compensation setting for all modes on the SPARK.REVLibError
enableSoftLimit(CANSparkBase.SoftLimitDirection direction, boolean enable)
Enable soft limitsREVLibError
enableVoltageCompensation(double nominalVoltage)
Sets the voltage compensation setting for all modes on the SPARK and enables voltage compensation.REVLibError
follow(CANSparkBase leader)
Causes this controller's output to mirror the provided leader.REVLibError
follow(CANSparkBase.ExternalFollower leader, int deviceID)
Causes this controller's output to mirror the provided leader.REVLibError
follow(CANSparkBase.ExternalFollower leader, int deviceID, boolean invert)
Causes this controller's output to mirror the provided leader.REVLibError
follow(CANSparkBase 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.SparkAbsoluteEncoder
getAbsoluteEncoder()
Returns an object for interfacing with a connected duty cycle absolute encoder.SparkAbsoluteEncoder
getAbsoluteEncoder(SparkAbsoluteEncoder.Type encoderType)
Returns an object for interfacing with a connected absolute encoder.SparkAbsoluteEncoder
getAbsoluteEncoder(SparkMaxAbsoluteEncoder.Type encoderType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAbsoluteEncoder(SparkAbsoluteEncoder.Type)
instead.SparkAnalogSensor
getAnalog()
Returns an object for interfacing with a connected analog sensor.SparkAnalogSensor
getAnalog(CANAnalog.AnalogMode mode)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAnalog(SparkAnalogSensor.Mode)
insteadSparkAnalogSensor
getAnalog(SparkAnalogSensor.Mode mode)
Returns an object for interfacing with a connected analog sensor.SparkAnalogSensor
getAnalog(SparkMaxAnalogSensor.Mode mode)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAnalog(SparkAnalogSensor.Mode)
insteaddouble
getAppliedOutput()
double
getBusVoltage()
double
getClosedLoopRampRate()
Get the configured closed loop ramp rateabstract RelativeEncoder
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 or the motor interface of the SPARK Flex.RelativeEncoder
getEncoder(EncoderType encoderType, int countsPerRev)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetEncoder(SparkMaxRelativeEncoder.Type, int)
instead.RelativeEncoder
getEncoder(SparkMaxRelativeEncoder.Type encoderType, int countsPerRev)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetEncoder(SparkRelativeEncoder.Type, int)
insteadRelativeEncoder
getEncoder(SparkRelativeEncoder.Type encoderType, int countsPerRev)
Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.boolean
getFault(CANSparkBase.FaultID faultID)
Get the value of a specific faultshort
getFaults()
protected int
getFeedbackDeviceID()
Gets the feedback device ID that was set on SPARK itself.SparkLimitSwitch
getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetForwardLimitSwitch(SparkLimitSwitch.Type)
instead.SparkLimitSwitch
getForwardLimitSwitch(SparkLimitSwitch.Type switchType)
Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.SparkLimitSwitch
getForwardLimitSwitch(SparkMaxLimitSwitch.Type switchType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetForwardLimitSwitch(SparkLimitSwitch.Type)
instead.CANSparkBase.IdleMode
getIdleMode()
Gets the idle mode setting for the SPARK.boolean
getInverted()
Common interface for returning the inversion state of a speed controller.REVLibError
getLastError()
All device errors are tracked on a per thread basis for all devices in that thread.double
getMotorTemperature()
double
getOpenLoopRampRate()
Get the configured open loop ramp ratedouble
getOutputCurrent()
SparkPIDController
getPIDController()
SparkLimitSwitch
getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetReverseLimitSwitch(SparkLimitSwitch.Type)
instead.SparkLimitSwitch
getReverseLimitSwitch(SparkLimitSwitch.Type switchType)
Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.SparkLimitSwitch
getReverseLimitSwitch(SparkMaxLimitSwitch.Type switchType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetReverseLimitSwitch(SparkLimitSwitch.Type)
instead.double
getSoftLimit(CANSparkBase.SoftLimitDirection direction)
Get the soft limit setting in the controllerboolean
getStickyFault(CANSparkBase.FaultID faultID)
Get the value of a specific sticky faultshort
getStickyFaults()
double
getVoltageCompensationNominalVoltage()
Get the configured voltage compensation nominal voltage valueboolean
isFollower()
Returns whether the controller is following another controllerboolean
isSoftLimitEnabled(CANSparkBase.SoftLimitDirection direction)
void
set(double speed)
Common interface for setting the speed of a speed controller.REVLibError
setCANTimeout(int milliseconds)
Sets timeout for sending CAN messages with SetParameter* and GetParameter* calls.REVLibError
setClosedLoopRampRate(double rate)
Sets the ramp rate for closed loop control modes.REVLibError
setIdleMode(CANSparkBase.IdleMode mode)
Sets the idle mode setting for the SPARK.void
setInverted(boolean isInverted)
Common interface for inverting direction of a speed controller.REVLibError
setOpenLoopRampRate(double rate)
Sets the ramp rate for open loop control modes.REVLibError
setSecondaryCurrentLimit(double limit)
Sets the secondary current limit in Amps.REVLibError
setSecondaryCurrentLimit(double limit, int chopCycles)
Sets the secondary current limit in Amps.REVLibError
setSmartCurrentLimit(int limit)
Sets the current limit in Amps.REVLibError
setSmartCurrentLimit(int stallLimit, int freeLimit)
Sets the current limit in Amps.REVLibError
setSmartCurrentLimit(int stallLimit, int freeLimit, int limitRPM)
Sets the current limit in Amps.REVLibError
setSoftLimit(CANSparkBase.SoftLimitDirection direction, float limit)
Set the soft limit based on position.void
setVoltage(double outputVolts)
Sets the voltage output of the SpeedController.void
stopMotor()
-
Methods inherited from class com.revrobotics.CANSparkLowLevel
close, enableExternalUSBControl, getDeviceId, getFirmwareString, getFirmwareVersion, getInitialMotorType, getMotorType, getSafeFloat, getSerialNumber, restoreFactoryDefaults, restoreFactoryDefaults, setCANMaxRetries, setControlFramePeriodMs, setPeriodicFramePeriod, setPeriodicFramePeriod, setPeriodicFrameTimeout, throwIfClosed
-
-
-
-
Constructor Detail
-
CANSparkBase
public CANSparkBase(int deviceId, CANSparkLowLevel.MotorType type, CANSparkLowLevel.SparkModel model)
Create a new object to control a SPARK 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 Detail
-
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()
-
getEncoder
public abstract RelativeEncoder 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 or the motor interface of the SPARK Flex.For a SPARK MAX in brushless mode, it is assumed that the default encoder type is hall effect and the counts per revolution is 42.
For a SPARK Flex in brushless mode, it is assumed that the default encoder type is quadrature and the counts per revolution is 7168.
- Returns:
- An object for interfacing with the integrated encoder.
-
getEncoder
public RelativeEncoder getEncoder(SparkRelativeEncoder.Type encoderType, int countsPerRev)
Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.- Parameters:
encoderType
- The encoder type for the motor: kHallEffect or kQuadraturecountsPerRev
- The counts per revolution of the encoder- Returns:
- An object for interfacing with an encoder
-
getEncoder
@Deprecated(forRemoval=true) public RelativeEncoder getEncoder(SparkMaxRelativeEncoder.Type encoderType, int countsPerRev)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetEncoder(SparkRelativeEncoder.Type, int)
insteadReturns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.- Parameters:
encoderType
- The encoder type for the motor: kHallEffect or kQuadraturecountsPerRev
- 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.UsegetEncoder(SparkMaxRelativeEncoder.Type, int)
instead.Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.- Parameters:
encoderType
- The encoder type for the motor: kHallEffect or kQuadraturecountsPerRev
- The counts per revolution of the encoder- Returns:
- An object for interfacing with an encoder
-
getAnalog
public SparkAnalogSensor getAnalog()
Returns an object for interfacing with a connected analog sensor. By default, the mode is set to kAbsolute, thus treating the sensor as an absolute sensor.- Returns:
- An object for interfacing with a connected analog sensor.
-
getAnalog
public SparkAnalogSensor getAnalog(SparkAnalogSensor.Mode mode)
Returns an object for interfacing with a connected analog sensor.- Parameters:
mode
- The mode of the analog sensor, either absolute or relative- Returns:
- An object for interfacing with a connected analog sensor.
-
getAnalog
@Deprecated(forRemoval=true) public SparkAnalogSensor getAnalog(SparkMaxAnalogSensor.Mode mode)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAnalog(SparkAnalogSensor.Mode)
insteadReturns an object for interfacing with a connected analog sensor.- Parameters:
mode
- The mode of the analog sensor, either absolute or relative- Returns:
- An object for interfacing with a connected analog sensor.
-
getAnalog
@Deprecated(forRemoval=true) public SparkAnalogSensor getAnalog(CANAnalog.AnalogMode mode)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAnalog(SparkAnalogSensor.Mode)
insteadReturns an object for interfacing with a connected analog sensor.- Parameters:
mode
- The mode of the analog sensor, either absolute or relative- Returns:
- An object for interfacing with a connected analog sensor.
-
getAbsoluteEncoder
public SparkAbsoluteEncoder getAbsoluteEncoder()
Returns an object for interfacing with a connected duty cycle absolute encoder.- Returns:
- An object for interfacing with a connected absolute encoder
-
getAbsoluteEncoder
public SparkAbsoluteEncoder getAbsoluteEncoder(SparkAbsoluteEncoder.Type encoderType)
Returns an object for interfacing with a connected absolute encoder.- Parameters:
encoderType
- The encoder type for the motor: currently only kDutyCycle- Returns:
- An object for interfacing with a connected absolute encoder
-
getAbsoluteEncoder
@Deprecated(forRemoval=true) public SparkAbsoluteEncoder getAbsoluteEncoder(SparkMaxAbsoluteEncoder.Type encoderType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetAbsoluteEncoder(SparkAbsoluteEncoder.Type)
instead.Returns an object for interfacing with a connected absolute encoder.- Parameters:
encoderType
- The encoder type for the motor: currently only kDutyCycle- Returns:
- An object for interfacing with a connected absolute encoder
-
getPIDController
public SparkPIDController getPIDController()
- Returns:
- An object for interfacing with the integrated PID controller.
-
getForwardLimitSwitch
@Deprecated(forRemoval=true) public SparkLimitSwitch getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetForwardLimitSwitch(SparkLimitSwitch.Type)
instead.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
@Deprecated(forRemoval=true) public SparkLimitSwitch getForwardLimitSwitch(SparkMaxLimitSwitch.Type switchType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetForwardLimitSwitch(SparkLimitSwitch.Type)
instead.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.
-
getForwardLimitSwitch
public SparkLimitSwitch getForwardLimitSwitch(SparkLimitSwitch.Type switchType)
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(forRemoval=true) public SparkLimitSwitch getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetReverseLimitSwitch(SparkLimitSwitch.Type)
instead.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
@Deprecated(forRemoval=true) public SparkLimitSwitch getReverseLimitSwitch(SparkMaxLimitSwitch.Type switchType)
Deprecated, for removal: This API element is subject to removal in a future version.UsegetReverseLimitSwitch(SparkLimitSwitch.Type)
instead.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.
-
getReverseLimitSwitch
public SparkLimitSwitch getReverseLimitSwitch(SparkLimitSwitch.Type switchType)
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
public REVLibError setIdleMode(CANSparkBase.IdleMode mode)
Sets the idle mode setting for the SPARK.- Parameters:
mode
- Idle mode (coast or brake).- Returns:
REVLibError.kOk
if successful
-
getIdleMode
public CANSparkBase.IdleMode getIdleMode()
Gets the idle mode setting for the SPARK.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 and enables voltage compensation.- Parameters:
nominalVoltage
- Nominal voltage to compensate output to- Returns:
REVLibError.kOk
if successful
-
disableVoltageCompensation
public REVLibError disableVoltageCompensation()
Disables the voltage compensation setting for all modes on the SPARK.- Returns:
REVLibError.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 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 rateThis 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 rateThis 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(CANSparkBase 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-enabled SPARK is not officially supported.
- Parameters:
leader
- The motor controller to follow.- Returns:
REVLibError.kOk
if successful
-
follow
public REVLibError follow(CANSparkBase 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-enabled SPARK 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(CANSparkBase.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-enabled SPARK 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(CANSparkBase.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-enabled SPARK 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(CANSparkBase.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(CANSparkBase.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 REVLibError clearFaults()
Clears all sticky faults.- Returns:
REVLibError.kOk
if successful
-
burnFlash
public REVLibError 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(CANSparkBase.SoftLimitDirection direction, boolean enable)
Enable soft limits- Parameters:
direction
- the direction of motion to restrictenable
- set true to enable soft limits- Returns:
REVLibError.kOk
if successful
-
setSoftLimit
public REVLibError setSoftLimit(CANSparkBase.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:
REVLibError.kOk
if successful
-
getSoftLimit
public double getSoftLimit(CANSparkBase.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(CANSparkBase.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 SPARK itself.- Returns:
- Feedback device ID on the SPARK
-
getLastError
public REVLibError 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.
-
-