Class Microsystem

java.lang.Object
tagalong.subsystems.micro.Microsystem
Direct Known Subclasses:
Elevator, Pivot, Roller

public class Microsystem extends Object
Base class for all Tagalong Microsystems
  • Field Details

  • Constructor Details

    • Microsystem

      Constructs a microsystem with the below configurations
      Parameters:
      conf - Configuration for the microsystem
  • Method Details

    • configAllDevices

      public void configAllDevices()
      Configures devices
    • setBrakeMode

      public void setBrakeMode(boolean enabled)
      Sets all motors on enable brake mode
      Parameters:
      enabled - whether or not the robot is enabled
    • updateAllPIDSGVA

      public void updateAllPIDSGVA()
    • onEnable

      public void onEnable()
      Sets break mode for all motors If system is in PID tuning mode is updates all PID related settings If the system is in Feedforward Tuning mode, it sets the primary motor to coast mode.
    • waitForInitialization

      protected void waitForInitialization()
      Checks initialize status
    • checkInitStatus

      public boolean checkInitStatus()
      checks to see if micro system is enabled and primary motor is alive
      Returns:
      boolean
    • getPrimaryMotor

      public com.ctre.phoenix6.hardware.TalonFX getPrimaryMotor()
      Returns:
      _primaryMotor(if system is enabled)
    • getPrimaryMotorPosition

      public double getPrimaryMotorPosition()
      Returns:
      position of the primary motor, 0.0 if system is disabled
    • getPrimaryMotorVelocity

      public double getPrimaryMotorVelocity()
      Returns:
      velocity of the primary motor, 0.0 if system is disabled
    • setPrimaryPower

      public void setPrimaryPower(double power)
      exits method if micro system is disabled, if enabled sets primary motor to specified value
      Parameters:
      power - desired power
    • getPrimaryMotorPower

      public double getPrimaryMotorPower()
      Returns:
      double(0.0 if micro system is disabled or actual power of primary motor)
    • configTuningModes

      public void configTuningModes()
      configures the tuning states of the micro system based on whether it is selected for tuning, and whether it is in PID or feedforward tuning mode
    • configShuffleboard

      public void configShuffleboard()
      Configures a user interface on the Shuffleboard for the specified micro system
    • onDisable

      public void onDisable()
      returns nothing if micro system is disabled
    • onTeleopDisable

      public void onTeleopDisable()
      returns nothing if micro system is disabled else it sets followProfile to false which stops any movement
    • setFollowProfile

      public void setFollowProfile(boolean followProfile)
      control whether the robot or subsystem should follow a predefined motion path
      Parameters:
      followProfile - whether or not to follow the trapezoidal profile
    • setHoldPosition

      public void setHoldPosition(boolean holdPosition)
      alias for setFollowProfile
      Parameters:
      holdPosition - whether or not to hold position
    • motorResetConfig

      public boolean motorResetConfig()
      Returns:
      boolean (micro system is enabled and the primary motor has been reset and if successful, it reconfigures the devices and returns true)
    • isProfileFinished

      public boolean isProfileFinished()
      Checks if the trapezoidal profile has reached its goal
      Returns:
      whether or not the profile has finished
    • disableMicrosystem

      public void disableMicrosystem(boolean disable)
      Sets microsystem disablement
      Parameters:
      disable - whether or not the microsystem should be disabled
    • holdCurrentPosition

      public void holdCurrentPosition()
      Sets the power of the primary motor to zero
    • updateShuffleboard

      public void updateShuffleboard()
      Updates shuffleboard
    • periodic

      public void periodic()
      Periodic update function
    • simulationInit

      public void simulationInit()
      Initializes simulation
    • simulationPeriodic

      public void simulationPeriodic()
      Periodic function during simulation
    • resetToleranceTimer

      public void resetToleranceTimer()
      Resets the tolerance timer, must be ran as part of command initialization
    • checkToleranceTime

      public boolean checkToleranceTime(boolean inTolerance, double requiredDurationS)
      Ran each time the isFinished command is run when in tolerance duration is required. Resets or starts the timer accordingly and evaluates if required duration has been met
      Parameters:
      inTolerance - True if the microsystem is currently in tolerance
      requiredDurationS - Require in tolerance duration in seconds
      Returns:
      True if the microsystem has been in tolerance the required duration
    • getRoot

      Returns:
      sim root