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
Direct Known Subclasses:
Climb, Elbow, Elevator, Intake, Shoulder, Twist

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
  • Field Details

    • motor

      protected com.ctre.phoenix6.hardware.TalonFX motor
    • followerMotors

      protected com.ctre.phoenix6.hardware.TalonFX[] followerMotors
    • config

      public Mechanism.Config config
  • Constructor Details

  • Method Details

    • telemetryInit

      public void telemetryInit()
    • periodic

      public void periodic()
      Specified by:
      periodic in interface edu.wpi.first.wpilibj2.command.Subsystem
    • simulationPeriodic

      public void simulationPeriodic()
      Specified by:
      simulationPeriodic in interface edu.wpi.first.wpilibj2.command.Subsystem
    • getName

      public String getName()
      Specified by:
      getName in interface edu.wpi.first.wpilibj2.command.Subsystem
    • isAttached

      public boolean isAttached()
    • initSendable

      public void initSendable(edu.wpi.first.networktables.NTSendableBuilder builder)
      Specified by:
      initSendable in interface edu.wpi.first.networktables.NTSendable
    • getCurrentCommandName

      protected String getCurrentCommandName()
    • runningDefaultCommand

      public Trigger runningDefaultCommand()
    • getTarget

      public double getTarget()
    • atTargetPosition

      public Trigger atTargetPosition(DoubleSupplier tolerance)
    • atRotations

      public Trigger atRotations(DoubleSupplier target, DoubleSupplier tolerance)
    • belowRotations

      public Trigger belowRotations(DoubleSupplier target, DoubleSupplier tolerance)
    • aboveRotations

      public Trigger aboveRotations(DoubleSupplier target, DoubleSupplier tolerance)
    • atPercentage

      public Trigger atPercentage(DoubleSupplier target, DoubleSupplier tolerance)
    • belowPercentage

      public Trigger belowPercentage(DoubleSupplier target, DoubleSupplier tolerance)
    • abovePercentage

      public Trigger abovePercentage(DoubleSupplier target, DoubleSupplier tolerance)
    • atDegrees

      public Trigger atDegrees(DoubleSupplier target, DoubleSupplier tolerance)
    • belowDegrees

      public Trigger belowDegrees(DoubleSupplier target, DoubleSupplier tolerance)
    • aboveDegrees

      public Trigger aboveDegrees(DoubleSupplier target, DoubleSupplier tolerance)
    • atVelocityRPM

      public Trigger atVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance)
    • belowVelocityRPM

      public Trigger belowVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance)
    • aboveVelocityRPM

      public Trigger aboveVelocityRPM(DoubleSupplier target, DoubleSupplier tolerance)
    • atCurrent

      public Trigger atCurrent(DoubleSupplier target, DoubleSupplier tolerance)
    • belowCurrent

      public Trigger belowCurrent(DoubleSupplier target, DoubleSupplier tolerance)
    • aboveCurrent

      public Trigger aboveCurrent(DoubleSupplier target, DoubleSupplier tolerance)
    • 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

      public double percentToRotations(DoubleSupplier percent)
      Percentage to Rotations
      Returns:
    • rotationsToPercent

      public double rotationsToPercent(DoubleSupplier rotations)
      Rotations to Percentage
      Parameters:
      rotations -
      Returns:
    • degreesToRotations

      public double degreesToRotations(DoubleSupplier degrees)
      Degrees to Rotations
      Returns:
      rotations
    • rotationsToDegrees

      public double rotationsToDegrees(DoubleSupplier rotations)
      Rotations to Degrees
      Parameters:
      rotations -
      Returns:
      degrees
    • getPositionRotations

      public double getPositionRotations()
    • getPositionPercentage

      public double getPositionPercentage()
    • getPositionDegrees

      public double getPositionDegrees()
    • getVelocityRPM

      public double getVelocityRPM()
    • runVelocity

      public edu.wpi.first.wpilibj2.command.Command runVelocity(DoubleSupplier velocityRPM)
      Runs the Mechanism at a given velocity
      Parameters:
      velocityRPM - in revolutions per minute
    • runVelocityTcFocRpm

      public edu.wpi.first.wpilibj2.command.Command runVelocityTcFocRpm(DoubleSupplier velocityRPM)
      Run the mechanism at given velocity rpm in TorqueCurrentFOC mode
      Parameters:
      velocityRPM -
      Returns:
    • runPercentage

      public edu.wpi.first.wpilibj2.command.Command runPercentage(DoubleSupplier percent)
    • runVoltage

      public edu.wpi.first.wpilibj2.command.Command runVoltage(DoubleSupplier voltage)
    • runTorqueCurrentFoc

      public edu.wpi.first.wpilibj2.command.Command runTorqueCurrentFoc(DoubleSupplier current)
    • moveToRotations

      public edu.wpi.first.wpilibj2.command.Command moveToRotations(DoubleSupplier rotations)
      Run to the specified position.
      Parameters:
      rotations - position in revolutions
    • moveToPercentage

      public edu.wpi.first.wpilibj2.command.Command moveToPercentage(DoubleSupplier percent)
      Move to the specified position.
      Parameters:
      percent - position in percentage of max revolutions
    • moveToDegrees

      public edu.wpi.first.wpilibj2.command.Command moveToDegrees(DoubleSupplier degrees)
      Move to the specified position.
      Parameters:
      degrees - position in degrees
    • runFocRotations

      public edu.wpi.first.wpilibj2.command.Command runFocRotations(DoubleSupplier rotations)
      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

      protected void setCurrentLimits(DoubleSupplier supplyLimit, DoubleSupplier statorLimit)
    • stop

      protected void stop()
    • tareMotor

      protected void tareMotor()
      Sets the mechanism position of the motor to 0
    • setMotorPosition

      protected void setMotorPosition(DoubleSupplier rotations)
      Sets the mechanism position of the motor
      Parameters:
      rotations - rotations
    • setMMVelocityFOC

      protected void setMMVelocityFOC(DoubleSupplier velocityRPS)
      Closed-loop Velocity Motion Magic with torque control (requires Pro)
      Parameters:
      velocityRPS - rotations per second
    • setVelocityTorqueCurrentFOC

      protected void setVelocityTorqueCurrentFOC(DoubleSupplier velocityRPS)
      Closed-loop Velocity with torque control (requires Pro)
      Parameters:
      velocityRPS - rotations per second
    • setVelocityTCFOCrpm

      protected void setVelocityTCFOCrpm(DoubleSupplier velocityRPS)
      Closed-loop Velocity with torque control (requires Pro)
      Parameters:
      velocity - rotations per second
    • setVelocity

      protected void setVelocity(DoubleSupplier velocityRPS)
      Closed-loop velocity control with voltage compensation
      Parameters:
      velocityRPS - rotations per second
    • setMMPositionFoc

      protected void setMMPositionFoc(DoubleSupplier rotations)
      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

      protected void setMMPosition(DoubleSupplier rotations)
      Closed-loop Position Motion Magic
      Parameters:
      rotations - rotations
    • setMMPosition

      public void setMMPosition(DoubleSupplier rotations, int slot)
      Closed-loop Position Motion Magic using a slot other than 0
      Parameters:
      rotations - rotations
      slot - gains slot
    • setPercentOutput

      public void setPercentOutput(DoubleSupplier percent)
      Open-loop Percent output control with voltage compensation
      Parameters:
      percent - fractional units between -1 and +1
    • setVoltageOutput

      public void setVoltageOutput(DoubleSupplier voltage)
    • setTorqueCurrentFoc

      public void setTorqueCurrentFoc(DoubleSupplier current)
    • setBrakeMode

      public void setBrakeMode(boolean isInBrake)
    • toggleReverseSoftLimit

      public void toggleReverseSoftLimit(boolean enabled)
    • toggleTorqueCurrentLimit

      public void toggleTorqueCurrentLimit(DoubleSupplier enabledLimit, boolean enabled)
    • toggleSupplyCurrentLimit

      public void toggleSupplyCurrentLimit(DoubleSupplier enabledLimit, boolean enabled)
    • applyCurrentLimit

      public void applyCurrentLimit(DoubleSupplier supplyLimit, DoubleSupplier statorLimit)
    • checkAvgCurrent

      public edu.wpi.first.wpilibj2.command.Command checkAvgCurrent(DoubleSupplier expectedCurrent, DoubleSupplier tolerance)
    • checkMaxCurrent

      public edu.wpi.first.wpilibj2.command.Command checkMaxCurrent(DoubleSupplier expectedCurrent)
    • 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()