Class SparkBase
- All Implemented Interfaces:
MotorController,AutoCloseable
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enumstatic classstatic enumstatic enumstatic classNested classes/interfaces inherited from class com.revrobotics.spark.SparkLowLevel
SparkLowLevel.MotorType, SparkLowLevel.PeriodicFrame, SparkLowLevel.PeriodicStatus0, SparkLowLevel.PeriodicStatus1, SparkLowLevel.PeriodicStatus2, SparkLowLevel.SparkModel -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected SparkAbsoluteEncoderprotected final Objectprotected SparkAnalogSensorprotected final Objectprotected SparkClosedLoopControllerprotected final Objectprotected SparkRelativeEncoderprotected final Objectprotected SparkLimitSwitchprotected final Objectprotected SparkSoftLimitprotected final Objectprotected SparkLimitSwitchprotected final Objectprotected SparkSoftLimitprotected final ObjectFields inherited from class com.revrobotics.spark.SparkLowLevel
expectedSparkModel, isClosed, kAPIBuildVersion, kAPIMajorVersion, kAPIMinorVersion, kAPIVersion, motorType, sparkHandle -
Constructor Summary
ConstructorsConstructorDescriptionSparkBase(int deviceId, SparkLowLevel.MotorType type, SparkLowLevel.SparkModel model) Create a new object to control a SPARK motor Controller -
Method Summary
Modifier and TypeMethodDescriptionClears all sticky faults.configure(SparkBaseConfig config, SparkBase.ResetMode resetMode, SparkBase.PersistMode persistMode) Set the configuration for the SPARK.configureAsync(SparkBaseConfig config, SparkBase.ResetMode resetMode, SparkBase.PersistMode persistMode) Set the configuration for the SPARK without waiting for a response.voiddisable()Common interface for disabling a motor.doubleget()Common interface for getting the current set speed of a speed controller.Returns an object for interfacing with a connected absolute encoder.Returns an object for interfacing with a connected analog sensor.doubleSimulation note: this value will not be updated during simulation unlessSparkSim.iterate(double, double, double)is calleddoubleReturns 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.Get the active faults that are currently present on the SPARK.Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.Returns an object for interfacing with the forward soft limit.booleanDeprecated.All device errors are tracked on a per thread basis for all devices in that thread.doubledoubleReturns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.Returns an object for interfacing with the reverse soft limit.Get the sticky faults that were present on the SPARK at one point since the sticky faults were last cleared.Get the sticky warnings that were present on the SPARK at one point since the sticky warnings were last cleared.Get the active warnings that are currently present on the SPARK.booleanGet whether the SPARK has one or more active faults.booleanGet whether the SPARK has one or more active warnings.booleanGet whether the SPARK has one or more sticky faults.booleanGet whether the SPARK has one or more sticky warnings.booleanReturns whether the controller is following another controllerPause follower mode.Pause follower mode without waiting for a responseResume follower mode if the SPARK has a valid follower mode config.Resume follower mode if the SPARK has a valid follower mode config without waiting for a response.voidset(double speed) Common interface for setting the speed of a speed controller.setCANTimeout(int milliseconds) Sets the timeout duration for waiting for CAN responses from the device.voidsetInverted(boolean isInverted) Deprecated.voidsetVoltage(double outputVolts) Sets the voltage output of the SpeedController.voidMethods inherited from class com.revrobotics.spark.SparkLowLevel
close, createSimFaultManager, getDeviceId, getFirmwareString, getFirmwareVersion, getMotorType, getSafeFloat, getSerialNumber, setCANMaxRetries, setControlFramePeriodMs, setPeriodicFrameTimeout, throwIfClosedMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj.motorcontrol.MotorController
setVoltage
-
Field Details
-
encoder
-
encoderLock
-
analogSensor
-
analogSensorLock
-
absoluteEncoder
-
absoluteEncoderLock
-
closedLoopController
-
closedLoopControllerLock
-
forwardLimitSwitch
-
forwardLimitSwitchLock
-
reverseLimitSwitch
-
reverseLimitSwitchLock
-
forwardSoftLimit
-
forwardSoftLimitLock
-
reverseSoftLimit
-
reverseSoftLimitLock
-
-
Constructor Details
-
SparkBase
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 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
Deprecated.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
Deprecated.UseSparkBaseConfigAccessor.getInverted()viaSparkMax.configAccessororSparkFlex.configAccessorinstead.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() -
configure
public REVLibError configure(SparkBaseConfig config, SparkBase.ResetMode resetMode, SparkBase.PersistMode persistMode) Set the configuration for the SPARK.If
resetModeisSparkBase.ResetMode.kResetSafeParameters, this method will reset safe writable parameters to their default values before setting the given configuration. The following parameters will not be reset by this action: CAN ID, Motor Type, Idle Mode, PWM Input Deadband, and Duty Cycle Offset.If
persistModeisSparkBase.PersistMode.kPersistParameters, this method will save all parameters to the SPARK's non-volatile memory after setting the given configuration. This will allow parameters to persist across power cycles.- Parameters:
config- The desired SPARK configurationresetMode- Whether to reset safe parameters before setting the configurationpersistMode- Whether to persist the parameters after setting the configuration- Returns:
REVLibError.kOkif successful
-
configureAsync
public REVLibError configureAsync(SparkBaseConfig config, SparkBase.ResetMode resetMode, SparkBase.PersistMode persistMode) Set the configuration for the SPARK without waiting for a response.If
resetModeisSparkBase.ResetMode.kResetSafeParameters, this method will reset safe writable parameters to their default values before setting the given configuration. The following parameters will not be reset by this action: CAN ID, Motor Type, Idle Mode, PWM Input Deadband, and Duty Cycle Offset.If
persistModeisSparkBase.PersistMode.kPersistParameters, this method will save all parameters to the SPARK's non-volatile memory after setting the given configuration. This will allow parameters to persist across power cycles.NOTE: This method will immediately return
REVLibError.kOkand the action will be done in the background. Any errors that occur will be reported to the driver station.- Parameters:
config- The desired SPARK configurationresetMode- Whether to reset safe parameters before setting the configurationpersistMode- Whether to persist the parameters after setting the configuration- Returns:
REVLibError.kOk
-
getEncoder
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.- Returns:
- An object for interfacing with an encoder
-
getAnalog
Returns an object for interfacing with a connected analog sensor.- Returns:
- An object for interfacing with a connected analog sensor.
-
getAbsoluteEncoder
Returns an object for interfacing with a connected absolute encoder.- Returns:
- An object for interfacing with a connected absolute encoder
-
getClosedLoopController
- Returns:
- An object for interfacing with the integrated closed loop controller.
-
getForwardLimitSwitch
Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.- Returns:
- An object for interfacing with the forward limit switch.
-
getReverseLimitSwitch
Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.- Returns:
- An object for interfacing with the reverse limit switch.
-
getForwardSoftLimit
Returns an object for interfacing with the forward soft limit.- Returns:
- An object for interfacing with the forward soft limit.
-
getReverseSoftLimit
Returns an object for interfacing with the reverse soft limit.- Returns:
- An object for interfacing with the reverse soft limit.
-
resumeFollowerMode
Resume follower mode if the SPARK has a valid follower mode config.NOTE: Follower mode will start automatically upon configuring follower mode. If the SPARK experiences a power cycle and has follower mode configured, follower mode will automatically restart. This method is only useful after
pauseFollowerMode()has been called.- Returns:
REVLibError.kOkif successful
-
resumeFollowerModeAsync
Resume follower mode if the SPARK has a valid follower mode config without waiting for a response.NOTE: Follower mode will start automatically upon configuring follower mode. If the SPARK experiences a power cycle and has follower mode configured, follower mode will automatically restart. This method is only useful after
pauseFollowerMode()has been called.NOTE: This method will immediately return
REVLibError.kOkand the action will be done in the background. Any errors that occur will be reported to the driver station.- Returns:
REVLibError.kOk- See Also:
-
pauseFollowerMode
Pause follower mode.NOTE: If the SPARK experiences a power cycle and has follower mode configured, follower mode will automatically restart.
- Returns:
REVLibError.kOkif successful
-
pauseFollowerModeAsync
Pause follower mode without waiting for a responseNOTE: If the SPARK experiences a power cycle and has follower mode configured, follower mode will automatically restart.
NOTE: This method will immediately return
REVLibError.kOkand the action will be done in the background. Any errors that occur will be reported to the driver station.- Returns:
REVLibError.kOk- See Also:
-
isFollower
public boolean isFollower()Returns whether the controller is following another controller- Returns:
- True if this device is following another controller false otherwise
-
hasActiveFault
public boolean hasActiveFault()Get whether the SPARK has one or more active faults.- Returns:
- true if there is an active fault
- See Also:
-
hasStickyFault
public boolean hasStickyFault()Get whether the SPARK has one or more sticky faults.- Returns:
- true if there is a sticky fault
- See Also:
-
hasActiveWarning
public boolean hasActiveWarning()Get whether the SPARK has one or more active warnings.- Returns:
- true if there is an active warning
- See Also:
-
hasStickyWarning
public boolean hasStickyWarning()Get whether the SPARK has one or more sticky warnings.- Returns:
- true if there is a sticky warning
- See Also:
-
getFaults
Get the active faults that are currently present on the SPARK. Faults are fatal errors that prevent the motor from running.- Returns:
- A struct with each fault and their active value
-
getStickyFaults
Get the sticky faults that were present on the SPARK at one point since the sticky faults were last cleared. Faults are fatal errors that prevent the motor from running.Sticky faults can be cleared with
clearFaults().- Returns:
- A struct with each fault and their sticky value
-
getWarnings
Get the active warnings that are currently present on the SPARK. Warnings are non-fatal errors.- Returns:
- A struct with each warning and their active value
-
getStickyWarnings
Get the sticky warnings that were present on the SPARK at one point since the sticky warnings were last cleared. Warnings are non-fatal errors.Sticky warnings can be cleared with
clearFaults().- Returns:
- A struct with each warning and their sticky value
-
getBusVoltage
public double getBusVoltage()- Returns:
- The voltage fed into the motor controller.
-
getAppliedOutput
public double getAppliedOutput()Simulation note: this value will not be updated during simulation unlessSparkSim.iterate(double, double, double)is called- 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.kOkif successful
-
setCANTimeout
Sets the timeout duration for waiting for CAN responses from the device.- Parameters:
milliseconds- The timeout in milliseconds.- Returns:
REVLibError.kOkif successful
-
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.
-
SparkBaseConfigAccessor.getInverted()viaSparkMax.configAccessororSparkFlex.configAccessorinstead.