Package frclib.motor
Class FrcCANSparkMax
java.lang.Object
trclib.motor.TrcMotor
frclib.motor.FrcCANSparkMax
- All Implemented Interfaces:
TrcMotorController,TrcExclusiveSubsystem,TrcOdometrySensor
This class implements a SparkMAX motor controller by REV robototics. It extends the TrcMotor class and
implements the abstract methods required by TrcMotor to be compatible with the TRC library.
Reference manual and API doc of the motor controller can be found here:
http://www.revrobotics.com/sparkmax-users-manual/?mc_cid=a60a44dc08&mc_eid=1935741b98#section-2-3
https://codedocs.revrobotics.com/java/com/revrobotics/cansparkmax
https://docs.revrobotics.com/revlib/24-to-25
-
Nested Class Summary
Nested classes/interfaces inherited from class trclib.motor.TrcMotor
TrcMotor.ExternalSensors, TrcMotor.FollowerMotor, TrcMotor.PowerCompensationNested classes/interfaces inherited from interface trclib.robotcore.TrcExclusiveSubsystem
TrcExclusiveSubsystem.OwnershipParamsNested classes/interfaces inherited from interface trclib.sensor.TrcOdometrySensor
TrcOdometrySensor.Odometry -
Field Summary
FieldsModifier and TypeFieldDescriptioncom.revrobotics.spark.config.SparkMaxConfigfinal com.revrobotics.spark.SparkMaxFields inherited from class trclib.motor.TrcMotor
instanceName, motorGetPositionElapsedTimer, motorSetCurrentElapsedTimer, motorSetPositionElapsedTimer, motorSetPowerElapsedTimer, motorSetVelocityElapsedTimer, tracer -
Constructor Summary
ConstructorsConstructorDescriptionFrcCANSparkMax(String instanceName, int canId, boolean brushless) Constructor: Create an instance of the object.FrcCANSparkMax(String instanceName, int canId, boolean brushless, boolean absEncoder) Constructor: Create an instance of the object.FrcCANSparkMax(String instanceName, int canId, boolean brushless, boolean absEncoder, TrcMotor.ExternalSensors sensors) Constructor: Create an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionvoidThis method disables the forward limit switch.voidThis method disables the reverse limit switch.voidenableMotorFwdLimitSwitch(boolean normalClose) This method enables the forward limit switch and configures it to the specified type.voidenableMotorRevLimitSwitch(boolean normalClose) This method enables the reverse limit switch and configures it to the specified type.voidThis method sets this motor to follow another motor.doubleThis method returns the bus voltage of the motor controller.intThis method returns the number of error responses seen from the motor after sending a command.com.revrobotics.REVLibErrorThe method returns the last error code.doubleThis method returns the motor current.This method returns the PID coefficients of the motor controller's current PID controller.doubleThis method returns the motor position by reading the position sensor.This method returns the PID coefficients of the motor controller's position PID controller.doubleThis method gets the current motor power.doubleThis method returns the current motor velocity.This method returns the PID coefficients of the motor controller's velocity PID controller.booleanThis method returns the motor type.booleanThis method returns the state of the forward limit switch.booleanThis method checks if the forward limit switch is enabled.booleanThis method checks if the motor direction is inverted.booleanThis method returns the state of the position sensor direction.booleanThis method returns the state of the reverse limit switch.booleanThis method checks if the reverse limit switch is enabled.booleanThis method checks if voltage compensation is enabled.voidThis method resets the motor controller configurations to factory default so that everything is at known state.voidThis method resets the motor position sensor, typically an encoder.voidresetMotorPosition(boolean hardware) This method resets the motor position sensor, typically an encoder.voidsetBrakeModeEnabled(boolean enabled) This method enables/disables motor brake mode.voidsetCloseLoopRampRate(double rampTime) This method sets the close loop ramp rate.voidsetCurrentLimit(double currentLimit, double triggerThresholdCurrent, double triggerThresholdTime) This method sets the current limit of the motor.voidsetMotorCurrent(double current) This method commands the motor to spin at the given current value using close loop control.voidThis method sets the PID coefficients of the motor controller's current PID controller.voidsetMotorFwdLimitSwitchInverted(boolean inverted) This method inverts the active state of the forward limit switch, typically reflecting whether the switch is wired normally open or normally close.voidThis method sets the soft position limit for the forward direction.voidsetMotorInverted(boolean inverted) This method inverts the spinning direction of the motor.voidsetMotorPosition(double position, Double powerLimit, double velocity, double feedForward) This method commands the motor to go to the given position using close loop control and optionally limits the power of the motor movement.voidThis method sets the PID coefficients of the motor controller's position PID controller.voidsetMotorPositionSensorInverted(boolean inverted) This method inverts the position sensor direction.voidsetMotorPower(double power) This method sets the raw motor power.voidsetMotorRevLimitSwitchInverted(boolean inverted) This method inverts the active state of the reverse limit switch, typically reflecting whether the switch is wired normally open or normally close.voidThis method sets the soft position limit for the reverse direction.voidsetMotorVelocity(double velocity, double acceleration, double feedForward) This method commands the motor to spin at the given velocity using close loop control.voidThis method sets the PID coefficients of the motor controller's velocity PID controller.voidsetOpenLoopRampRate(double rampTime) This method sets the open loop ramp rate.voidsetStatorCurrentLimit(double currentLimit) This method sets the stator current limit of the motor.voidsetVoltageCompensationEnabled(Double batteryNominalVoltage) This method enables/disables voltage compensation so that it will maintain the motor output regardless of battery voltage.Methods inherited from class trclib.motor.TrcMotor
addFollower, cancel, clearOdometryMotorsList, convertPositionToScaledUnits, convertPositionToSensorUnits, disableLowerLimitSwitch, disableMotionProfile, disableUpperLimitSwitch, enableLowerLimitSwitch, enableMotionProfile, enableUpperLimitSwitch, follow, getCurrent, getCurrentOnTarget, getCurrentPidCoefficients, getCurrentPidController, getEncoderRawPosition, getFollower, getName, getNumOdometryMotors, getOdometry, getPidTarget, getPosition, getPositionOnTarget, getPositionPidCoefficients, getPositionPidController, getPower, getVelocity, getVelocityOnTarget, getVelocityPidCoefficients, getVelocityPidController, isCalibrating, isLowerLimitSwitchActive, isLowerLimitSwitchEnabled, isOdometryEnabled, isPositionSensorInverted, isUpperLimitSwitchActive, isUpperLimitSwitchEnabled, presetPositionDown, presetPositionUp, presetVelocityDown, presetVelocityUp, printElapsedTime, printPidControlTaskPerformance, resetOdometry, resetPosition, resetPosition, resetPositionOnLowerLimitSwitch, resetPositionOnLowerLimitSwitch, resetPositionOnLowerLimitSwitch, resetPositionOnLowerLimitSwitch, setBeep, setBeep, setCurrent, setCurrent, setCurrent, setCurrent, setCurrentPidParameters, setCurrentPidParameters, setCurrentPidParameters, setCurrentPidPowerComp, setCurrentPidTolerance, setElapsedTimerEnabled, setLimitSwitchesSwapped, setLowerLimitSwitchInverted, setOdometryEnabled, setPerformanceMonitorEnabled, setPidPower, setPidPower, setPidStallDetectionEnabled, setPidStallDetectionEnabled, setPosition, setPosition, setPosition, setPosition, setPosition, setPosition, setPosition, setPositionPidParameters, setPositionPidParameters, setPositionPidParameters, setPositionPidPowerComp, setPositionPidTolerance, setPositionSensorInverted, setPositionSensorScaleAndOffset, setPositionSensorScaleAndOffset, setPower, setPower, setPower, setPower, setPresetPosition, setPresets, setPresetVelocity, setSoftPositionLimits, setSoftwarePidEnabled, setStallProtection, setTraceLevel, setUpperLimitSwitchInverted, setVelocity, setVelocity, setVelocity, setVelocity, setVelocityParameters, setVelocityPidParameters, setVelocityPidParameters, setVelocityPidPowerComp, setVelocityPidTolerance, stop, toString, zeroCalibrate, zeroCalibrate, zeroCalibrate, zeroCalibrate, zeroCalibrate, zeroCalibrateMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, waitMethods inherited from interface trclib.robotcore.TrcExclusiveSubsystem
acquireExclusiveAccess, acquireOwnership, cancelExclusiveAccess, getCurrentOwner, hasOwnership, releaseExclusiveAccess, releaseOwnership, validateOwnershipMethods inherited from interface trclib.sensor.TrcOdometrySensor
getOdometries, getOdometry
-
Field Details
-
motor
public final com.revrobotics.spark.SparkMax motor -
config
public com.revrobotics.spark.config.SparkMaxConfig config
-
-
Constructor Details
-
FrcCANSparkMax
public FrcCANSparkMax(String instanceName, int canId, boolean brushless, boolean absEncoder, TrcMotor.ExternalSensors sensors) Constructor: Create an instance of the object.- Parameters:
instanceName- specifies the instance name.canId- specifies the CAN ID of the device.brushless- specifies true if the motor is brushless, false otherwise.absEncoder- specifies true if uses DutyCycle absolute encoder, false to use relative encoder.sensors- specifies external sensors, can be null if none.
-
FrcCANSparkMax
Constructor: Create an instance of the object.- Parameters:
instanceName- specifies the instance name.canId- specifies the CAN ID of the device.brushless- specifies true if the motor is brushless, false otherwise.absEncoder- specifies true if uses DutyCycle absolute encoder, false to use relative encoder.
-
FrcCANSparkMax
Constructor: Create an instance of the object.- Parameters:
instanceName- specifies the instance name.canId- specifies the CAN ID of the device.brushless- specifies true if the motor is brushless, false otherwise.
-
-
Method Details
-
getErrorCount
public int getErrorCount()This method returns the number of error responses seen from the motor after sending a command.- Returns:
- The number of non-OK error code responses seen from the motor after sending a command.
-
getLastError
public com.revrobotics.REVLibError getLastError()The method returns the last error code. If there is none, null is returned.- Returns:
- last error code.
-
isBrushless
public boolean isBrushless()This method returns the motor type.- Returns:
- true if the motor is brushless, false otherwise.
-
resetFactoryDefault
public void resetFactoryDefault()This method resets the motor controller configurations to factory default so that everything is at known state. -
getBusVoltage
public double getBusVoltage()This method returns the bus voltage of the motor controller.- Returns:
- bus voltage of the motor controller.
-
setCurrentLimit
public void setCurrentLimit(double currentLimit, double triggerThresholdCurrent, double triggerThresholdTime) This method sets the current limit of the motor.- Parameters:
currentLimit- specifies the current limit (holding current) in amperes when feature is activated.triggerThresholdCurrent- not used. SparkMax does not support this.triggerThresholdTime- not used. SparkMax does not support this.
-
setStatorCurrentLimit
public void setStatorCurrentLimit(double currentLimit) This method sets the stator current limit of the motor.- Parameters:
currentLimit- specifies the stator current limit in amperes.
-
setCloseLoopRampRate
public void setCloseLoopRampRate(double rampTime) This method sets the close loop ramp rate.- Parameters:
rampTime- specifies the ramp time in seconds from neutral to full speed.
-
setOpenLoopRampRate
public void setOpenLoopRampRate(double rampTime) This method sets the open loop ramp rate.- Parameters:
rampTime- specifies the ramp time in seconds from neutral to full speed.
-
setBrakeModeEnabled
public void setBrakeModeEnabled(boolean enabled) This method enables/disables motor brake mode. In motor brake mode, set power to 0 would stop the motor very abruptly by shorting the motor wires together using the generated back EMF to stop the motor. When not enabled, (i.e. float/coast mode), the motor wires are just disconnected from the motor controller so the motor will stop gradually.- Parameters:
enabled- specifies true to enable brake mode, false otherwise.
-
enableMotorRevLimitSwitch
public void enableMotorRevLimitSwitch(boolean normalClose) This method enables the reverse limit switch and configures it to the specified type.- Parameters:
normalClose- specifies true as the normal close switch type, false as normal open.
-
enableMotorFwdLimitSwitch
public void enableMotorFwdLimitSwitch(boolean normalClose) This method enables the forward limit switch and configures it to the specified type.- Parameters:
normalClose- specifies true as the normal close switch type, false as normal open.
-
disableMotorRevLimitSwitch
public void disableMotorRevLimitSwitch()This method disables the reverse limit switch. -
disableMotorFwdLimitSwitch
public void disableMotorFwdLimitSwitch()This method disables the forward limit switch. -
isMotorRevLimitSwitchEnabled
public boolean isMotorRevLimitSwitchEnabled()This method checks if the reverse limit switch is enabled.- Returns:
- true if enabled, false if disabled.
-
isMotorFwdLimitSwitchEnabled
public boolean isMotorFwdLimitSwitchEnabled()This method checks if the forward limit switch is enabled.- Returns:
- true if enabled, false if disabled.
-
setMotorRevLimitSwitchInverted
public void setMotorRevLimitSwitchInverted(boolean inverted) This method inverts the active state of the reverse limit switch, typically reflecting whether the switch is wired normally open or normally close.- Parameters:
inverted- specifies true to invert the limit switch to normal close, false to normal open.
-
setMotorFwdLimitSwitchInverted
public void setMotorFwdLimitSwitchInverted(boolean inverted) This method inverts the active state of the forward limit switch, typically reflecting whether the switch is wired normally open or normally close.- Parameters:
inverted- specifies true to invert the limit switch to normal close, false to normal open.
-
isMotorRevLimitSwitchActive
public boolean isMotorRevLimitSwitchActive()This method returns the state of the reverse limit switch.- Returns:
- true if reverse limit switch is active, false otherwise.
-
isMotorFwdLimitSwitchActive
public boolean isMotorFwdLimitSwitchActive()This method returns the state of the forward limit switch.- Returns:
- true if forward limit switch is active, false otherwise.
-
setMotorRevSoftPositionLimit
This method sets the soft position limit for the reverse direction.- Parameters:
limit- specifies the limit in sensor units, null to disable.
-
setMotorFwdSoftPositionLimit
This method sets the soft position limit for the forward direction.- Parameters:
limit- specifies the limit in sensor units, null to disable.
-
setMotorPositionSensorInverted
public void setMotorPositionSensorInverted(boolean inverted) This method inverts the position sensor direction. This may be rare but there are scenarios where the motor encoder may be mounted somewhere in the power train that it rotates opposite to the motor rotation. This will cause the encoder reading to go down when the motor is receiving positive power. This method can correct this situation.- Parameters:
inverted- specifies true to invert position sensor direction, false otherwise.
-
isMotorPositionSensorInverted
public boolean isMotorPositionSensorInverted()This method returns the state of the position sensor direction.- Returns:
- true if the motor direction is inverted, false otherwise.
-
resetMotorPosition
public void resetMotorPosition(boolean hardware) This method resets the motor position sensor, typically an encoder. -
resetMotorPosition
public void resetMotorPosition()This method resets the motor position sensor, typically an encoder. -
setMotorInverted
public void setMotorInverted(boolean inverted) This method inverts the spinning direction of the motor.- Parameters:
inverted- specifies true to invert motor direction, false otherwise.
-
isMotorInverted
public boolean isMotorInverted()This method checks if the motor direction is inverted.- Returns:
- true if motor direction is inverted, false otherwise.
-
setMotorPower
public void setMotorPower(double power) This method sets the raw motor power.- Parameters:
power- specifies the percentage power (range -1.0 to 1.0) to be set.
-
getMotorPower
public double getMotorPower()This method gets the current motor power.- Returns:
- current motor power.
-
setMotorVelocity
public void setMotorVelocity(double velocity, double acceleration, double feedForward) This method commands the motor to spin at the given velocity using close loop control.- Parameters:
velocity- specifies the motor velocity in rotations per second.acceleration- specifies the max motor acceleration rotations per second square (not supported).feedForward- specifies feedforward in volts if voltage comp is ON, otherwise fractional unit between -1 and 1 (not supported).
-
getMotorVelocity
public double getMotorVelocity()This method returns the current motor velocity.- Returns:
- current motor velocity in rotations per second.
-
setMotorPosition
public void setMotorPosition(double position, Double powerLimit, double velocity, double feedForward) This method commands the motor to go to the given position using close loop control and optionally limits the power of the motor movement.- Parameters:
position- specifies the position in rotations.powerLimit- specifies the maximum power output limits, can be null if not provided. If not provided, the previous set limit is applied.velocity- specifies the max motor veloicty rotations per second (not supportec).feedForward- specifies feedforward in volts if voltage comp is ON, otherwise fractional unit between -1 and 1 (not supported).
-
getMotorPosition
public double getMotorPosition()This method returns the motor position by reading the position sensor.- Returns:
- current motor position in number of rotations.
-
setMotorCurrent
public void setMotorCurrent(double current) This method commands the motor to spin at the given current value using close loop control.- Parameters:
current- specifies current in amperes.
-
getMotorCurrent
public double getMotorCurrent()This method returns the motor current.- Returns:
- motor current in amperes.
-
setMotorVelocityPidCoefficients
This method sets the PID coefficients of the motor controller's velocity PID controller.- Parameters:
pidCoeff- specifies the PID coefficients to set.
-
getMotorVelocityPidCoefficients
This method returns the PID coefficients of the motor controller's velocity PID controller.- Returns:
- PID coefficients of the motor's veloicty PID controller.
-
setMotorPositionPidCoefficients
This method sets the PID coefficients of the motor controller's position PID controller.- Parameters:
pidCoeff- specifies the PID coefficients to set.
-
getMotorPositionPidCoefficients
This method returns the PID coefficients of the motor controller's position PID controller.- Returns:
- PID coefficients of the motor's position PID controller.
-
setMotorCurrentPidCoefficients
This method sets the PID coefficients of the motor controller's current PID controller.- Parameters:
pidCoeff- specifies the PID coefficients to set.
-
getMotorCurrentPidCoefficients
This method returns the PID coefficients of the motor controller's current PID controller.- Returns:
- PID coefficients of the motor's current PID controller.
-
setVoltageCompensationEnabled
This method enables/disables voltage compensation so that it will maintain the motor output regardless of battery voltage.- Specified by:
setVoltageCompensationEnabledin interfaceTrcMotorController- Overrides:
setVoltageCompensationEnabledin classTrcMotor- Parameters:
batteryNominalVoltage- specifies the nominal voltage of the battery to enable, null to disable.
-
isVoltageCompensationEnabled
public boolean isVoltageCompensationEnabled()This method checks if voltage compensation is enabled.- Specified by:
isVoltageCompensationEnabledin interfaceTrcMotorController- Overrides:
isVoltageCompensationEnabledin classTrcMotor- Returns:
- true if voltage compensation is enabled, false if disabled.
-
follow
This method sets this motor to follow another motor.- Specified by:
followin interfaceTrcMotorController- Overrides:
followin classTrcMotor- Parameters:
otherMotor- specifies the other motor to follow.inverted- specifies true if this motor is inverted from the motor it is following, false otherwise.scale- specifies the value scale for the follower motor, 1.0 by default.
-