Package frc.spectrumLib.mechanism
Class Mechanism
java.lang.Object
frc.spectrumLib.mechanism.Mechanism
- All Implemented Interfaces:
edu.wpi.first.networktables.NTSendable,edu.wpi.first.util.sendable.Sendable,edu.wpi.first.wpilibj2.command.Subsystem,SpectrumSubsystem
public abstract class Mechanism
extends Object
implements edu.wpi.first.networktables.NTSendable, SpectrumSubsystem
Control Modes Docs:
https://pro.docs.ctr-electronics.com/en/latest/docs/migration/migration-guide/control-requests-guide.html
Closed-loop & Motion Magic Docs:
https://pro.docs.ctr-electronics.com/en/latest/docs/migration/migration-guide/closed-loop-guide.html
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classstatic class -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected com.ctre.phoenix6.hardware.TalonFX[]protected com.ctre.phoenix6.hardware.TalonFX -
Constructor Summary
ConstructorsModifierConstructorDescriptionprotectedMechanism(Mechanism.Config config) protectedMechanism(Mechanism.Config config, boolean attached) -
Method Summary
Modifier and TypeMethodDescriptionaboveCurrent(DoubleSupplier target, DoubleSupplier tolerance) aboveDegrees(DoubleSupplier target, DoubleSupplier tolerance) abovePercentage(DoubleSupplier target, DoubleSupplier tolerance) aboveRotations(DoubleSupplier target, DoubleSupplier tolerance) aboveVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance) voidapplyCurrentLimit(DoubleSupplier supplyLimit, DoubleSupplier statorLimit) atCurrent(DoubleSupplier target, DoubleSupplier tolerance) atDegrees(DoubleSupplier target, DoubleSupplier tolerance) atPercentage(DoubleSupplier target, DoubleSupplier tolerance) atRotations(DoubleSupplier target, DoubleSupplier tolerance) atTargetPosition(DoubleSupplier tolerance) atVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance) belowCurrent(DoubleSupplier target, DoubleSupplier tolerance) belowDegrees(DoubleSupplier target, DoubleSupplier tolerance) belowPercentage(DoubleSupplier target, DoubleSupplier tolerance) belowRotations(DoubleSupplier target, DoubleSupplier tolerance) belowVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance) edu.wpi.first.wpilibj2.command.CommandcheckAvgCurrent(DoubleSupplier expectedCurrent, DoubleSupplier tolerance) edu.wpi.first.wpilibj2.command.CommandcheckMaxCurrent(DoubleSupplier expectedCurrent) edu.wpi.first.wpilibj2.command.CommandcheckMinThresholdCurrent(DoubleSupplier expectedCurrent) edu.wpi.first.wpilibj2.command.CommandTemporarily sets the mechanism to coast mode.doubledegreesToRotations(DoubleSupplier degrees) Degrees to Rotationsedu.wpi.first.wpilibj2.command.CommandSets the motor to brake mode if it is in coast modeprotected Stringcom.ctre.phoenix6.hardware.TalonFX[]com.ctre.phoenix6.hardware.TalonFXgetMotor()getName()doubledoubledoubledoubledoubledoubledoublevoidinitSendable(edu.wpi.first.networktables.NTSendableBuilder builder) booleanedu.wpi.first.wpilibj2.command.CommandmoveToDegrees(DoubleSupplier degrees) Move to the specified position.edu.wpi.first.wpilibj2.command.CommandmoveToPercentage(DoubleSupplier percent) Move to the specified position.edu.wpi.first.wpilibj2.command.CommandmoveToRotations(DoubleSupplier rotations) Run to the specified position.doublepercentToRotations(DoubleSupplier percent) Percentage to Rotationsvoidperiodic()doublerotationsToDegrees(DoubleSupplier rotations) Rotations to DegreesdoublerotationsToPercent(DoubleSupplier rotations) Rotations to Percentageprotected edu.wpi.first.wpilibj2.command.CommandrunCurrentLimits(DoubleSupplier supplyLimit, DoubleSupplier statorLimit) edu.wpi.first.wpilibj2.command.CommandrunFocRotations(DoubleSupplier rotations) Runs to the specified Motion Magic position using FOC control.edu.wpi.first.wpilibj2.command.CommandrunPercentage(DoubleSupplier percent) edu.wpi.first.wpilibj2.command.CommandrunStop()edu.wpi.first.wpilibj2.command.CommandrunTorqueCurrentFoc(DoubleSupplier current) edu.wpi.first.wpilibj2.command.CommandrunVelocity(DoubleSupplier velocityRPM) Runs the Mechanism at a given velocityedu.wpi.first.wpilibj2.command.CommandrunVelocityTcFocRpm(DoubleSupplier velocityRPM) Run the mechanism at given velocity rpm in TorqueCurrentFOC modeedu.wpi.first.wpilibj2.command.CommandrunVoltage(DoubleSupplier voltage) voidsetBrakeMode(boolean isInBrake) protected voidsetCurrentLimits(DoubleSupplier supplyLimit, DoubleSupplier statorLimit) protected voidsetDynMMPositionFoc(DoubleSupplier rotations, DoubleSupplier velocity, DoubleSupplier acceleration, DoubleSupplier jerk) Closed-loop Position Motion Magic with torque control (requires Pro) Dynamic allows you to set velocity, acceleration, and jerk during the commandprotected voidsetMMPosition(DoubleSupplier rotations) Closed-loop Position Motion MagicvoidsetMMPosition(DoubleSupplier rotations, int slot) Closed-loop Position Motion Magic using a slot other than 0protected voidsetMMPositionFoc(DoubleSupplier rotations) Closed-loop Position Motion Magic with torque control (requires Pro)protected voidsetMMVelocityFOC(DoubleSupplier velocityRPS) Closed-loop Velocity Motion Magic with torque control (requires Pro)protected voidsetMotorPosition(DoubleSupplier rotations) Sets the mechanism position of the motorvoidsetPercentOutput(DoubleSupplier percent) Open-loop Percent output control with voltage compensationvoidsetTorqueCurrentFoc(DoubleSupplier current) protected voidsetVelocity(DoubleSupplier velocityRPS) Closed-loop velocity control with voltage compensationprotected voidsetVelocityTCFOCrpm(DoubleSupplier velocityRPS) Closed-loop Velocity with torque control (requires Pro)protected voidsetVelocityTorqueCurrentFOC(DoubleSupplier velocityRPS) Closed-loop Velocity with torque control (requires Pro)voidsetVoltageOutput(DoubleSupplier voltage) voidprotected voidstop()protected voidSets the mechanism position of the motor to 0voidvoidtoggleReverseSoftLimit(boolean enabled) voidtoggleSupplyCurrentLimit(DoubleSupplier enabledLimit, boolean enabled) voidtoggleTorqueCurrentLimit(DoubleSupplier enabledLimit, boolean enabled) doubleUpdate the value of the stator current for the motordoubleMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.networktables.NTSendable
initSendableMethods inherited from interface frc.spectrumLib.SpectrumSubsystem
setupDefaultCommand, setupStatesMethods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, startEnd, startRun
-
Field Details
-
motor
protected com.ctre.phoenix6.hardware.TalonFX motor -
followerMotors
protected com.ctre.phoenix6.hardware.TalonFX[] followerMotors -
config
-
-
Constructor Details
-
Mechanism
-
Mechanism
-
-
Method Details
-
telemetryInit
public void telemetryInit() -
periodic
public void periodic()- Specified by:
periodicin interfaceedu.wpi.first.wpilibj2.command.Subsystem
-
simulationPeriodic
public void simulationPeriodic()- Specified by:
simulationPeriodicin interfaceedu.wpi.first.wpilibj2.command.Subsystem
-
getName
- Specified by:
getNamein interfaceedu.wpi.first.wpilibj2.command.Subsystem
-
isAttached
public boolean isAttached() -
initSendable
public void initSendable(edu.wpi.first.networktables.NTSendableBuilder builder) - Specified by:
initSendablein interfaceedu.wpi.first.networktables.NTSendable
-
getCurrentCommandName
-
runningDefaultCommand
-
getTarget
public double getTarget() -
atTargetPosition
-
atRotations
-
belowRotations
-
aboveRotations
-
atPercentage
-
belowPercentage
-
abovePercentage
-
atDegrees
-
belowDegrees
-
aboveDegrees
-
atVelocityRPM
-
belowVelocityRPM
-
aboveVelocityRPM
-
atCurrent
-
belowCurrent
-
aboveCurrent
-
updateCurrent
public double updateCurrent()Update the value of the stator current for the motor- Returns:
-
getStatorCurrent
public double getStatorCurrent() -
updateVoltage
public double updateVoltage() -
getVoltage
public double getVoltage() -
percentToRotations
Percentage to Rotations- Returns:
-
rotationsToPercent
Rotations to Percentage- Parameters:
rotations-- Returns:
-
degreesToRotations
Degrees to Rotations- Returns:
- rotations
-
rotationsToDegrees
Rotations to Degrees- Parameters:
rotations-- Returns:
- degrees
-
getPositionRotations
public double getPositionRotations() -
getPositionPercentage
public double getPositionPercentage() -
getPositionDegrees
public double getPositionDegrees() -
getVelocityRPM
public double getVelocityRPM() -
runVelocity
Runs the Mechanism at a given velocity- Parameters:
velocityRPM- in revolutions per minute
-
runVelocityTcFocRpm
Run the mechanism at given velocity rpm in TorqueCurrentFOC mode- Parameters:
velocityRPM-- Returns:
-
runPercentage
-
runVoltage
-
runTorqueCurrentFoc
-
moveToRotations
Run to the specified position.- Parameters:
rotations- position in revolutions
-
moveToPercentage
Move to the specified position.- Parameters:
percent- position in percentage of max revolutions
-
moveToDegrees
Move to the specified position.- Parameters:
degrees- position in degrees
-
runFocRotations
Runs to the specified Motion Magic position using FOC control. Will require different PID and feedforward configs- Parameters:
rotations- position in revolutions
-
runStop
public edu.wpi.first.wpilibj2.command.Command runStop() -
coastMode
public edu.wpi.first.wpilibj2.command.Command coastMode()Temporarily sets the mechanism to coast mode. The configuration is applied when the command is started and reverted when the command is ended. -
ensureBrakeMode
public edu.wpi.first.wpilibj2.command.Command ensureBrakeMode()Sets the motor to brake mode if it is in coast mode -
runCurrentLimits
protected edu.wpi.first.wpilibj2.command.Command runCurrentLimits(DoubleSupplier supplyLimit, DoubleSupplier statorLimit) -
setCurrentLimits
-
stop
protected void stop() -
tareMotor
protected void tareMotor()Sets the mechanism position of the motor to 0 -
setMotorPosition
Sets the mechanism position of the motor- Parameters:
rotations- rotations
-
setMMVelocityFOC
Closed-loop Velocity Motion Magic with torque control (requires Pro)- Parameters:
velocityRPS- rotations per second
-
setVelocityTorqueCurrentFOC
Closed-loop Velocity with torque control (requires Pro)- Parameters:
velocityRPS- rotations per second
-
setVelocityTCFOCrpm
Closed-loop Velocity with torque control (requires Pro)- Parameters:
velocity- rotations per second
-
setVelocity
Closed-loop velocity control with voltage compensation- Parameters:
velocityRPS- rotations per second
-
setMMPositionFoc
Closed-loop Position Motion Magic with torque control (requires Pro)- Parameters:
rotations- rotations
-
setDynMMPositionFoc
protected void setDynMMPositionFoc(DoubleSupplier rotations, DoubleSupplier velocity, DoubleSupplier acceleration, DoubleSupplier jerk) Closed-loop Position Motion Magic with torque control (requires Pro) Dynamic allows you to set velocity, acceleration, and jerk during the command- Parameters:
rotations-velocity-acceleration-jerk-
-
setMMPosition
Closed-loop Position Motion Magic- Parameters:
rotations- rotations
-
setMMPosition
Closed-loop Position Motion Magic using a slot other than 0- Parameters:
rotations- rotationsslot- gains slot
-
setPercentOutput
Open-loop Percent output control with voltage compensation- Parameters:
percent- fractional units between -1 and +1
-
setVoltageOutput
-
setTorqueCurrentFoc
-
setBrakeMode
public void setBrakeMode(boolean isInBrake) -
toggleReverseSoftLimit
public void toggleReverseSoftLimit(boolean enabled) -
toggleTorqueCurrentLimit
-
toggleSupplyCurrentLimit
-
applyCurrentLimit
-
checkAvgCurrent
public edu.wpi.first.wpilibj2.command.Command checkAvgCurrent(DoubleSupplier expectedCurrent, DoubleSupplier tolerance) -
checkMaxCurrent
-
checkMinThresholdCurrent
public edu.wpi.first.wpilibj2.command.Command checkMinThresholdCurrent(DoubleSupplier expectedCurrent) -
getMotor
public com.ctre.phoenix6.hardware.TalonFX getMotor() -
getFollowerMotors
public com.ctre.phoenix6.hardware.TalonFX[] getFollowerMotors()
-