Class Roller


public class Roller extends Microsystem
Roller microsystem
  • Field Details

  • Constructor Details

    • Roller

      public Roller(RollerConf conf)
      Constructs a roller microsystem with the below configurations
      Parameters:
      conf - Configuration for the roller
  • Method Details

    • onEnable

      public void onEnable()
      Description copied from class: Microsystem
      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.
      Overrides:
      onEnable in class Microsystem
    • onDisable

      public void onDisable()
      Description copied from class: Microsystem
      returns nothing if micro system is disabled
      Overrides:
      onDisable in class Microsystem
    • periodic

      public void periodic()
      Periodic update function
      Overrides:
      periodic in class Microsystem
    • simulationInit

      public void simulationInit()
      Description copied from class: Microsystem
      Initializes simulation
      Overrides:
      simulationInit in class Microsystem
    • simulationPeriodic

      public void simulationPeriodic()
      Description copied from class: Microsystem
      Periodic function during simulation
      Overrides:
      simulationPeriodic in class Microsystem
    • motorResetConfig

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

      public void updateShuffleboard()
      Description copied from class: Microsystem
      Updates shuffleboard
      Overrides:
      updateShuffleboard in class Microsystem
    • configShuffleboard

      public void configShuffleboard()
      Description copied from class: Microsystem
      Configures a user interface on the Shuffleboard for the specified micro system
      Overrides:
      configShuffleboard in class Microsystem
    • motorToRollerRot

      public double motorToRollerRot(double motorRot)
      Converts motor rotations to roller rotations
      Parameters:
      motorRot - motor rotations
      Returns:
      roller rotations converted from motor rotations
    • rollerRotToMotor

      public double rollerRotToMotor(double rollerRot)
      Converts motor rotations to roller rotations
      Parameters:
      rollerRot - roller rotations
      Returns:
      motor rotations converted from roller rotations
    • followLastProfile

      public void followLastProfile()
      Calculates the next state according to the trapezoidal profile and requests the roller motor(s) to arrive at the next position with feedforward
    • setRollerProfile

      public void setRollerProfile(Angle goalPosition)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPosition - goal position in rotations
    • setRollerProfile

      public void setRollerProfile(Angle goalPosition, double goalVelocityRPS)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPosition - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
    • setRollerProfile

      public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPosition - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
    • setRollerProfile

      public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPosition - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
      maxAccelerationRPS2 - maximum acceleration in rotations per second squared
    • setRollerProfile

      public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPosition - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
      maxAccelerationRPS2 - maximum acceleration in rotations per second squared
      setCurrentState - True if the profiles current state should base itself off sensor values rather than continue from the existing state
    • setRollerProfile

      public void setRollerProfile(double goalPositionRot)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPositionRot - goal position in rotations
    • setRollerProfile

      public void setRollerProfile(double goalPositionRot, double goalVelocityRPS)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPositionRot - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
    • setRollerProfile

      public void setRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPositionRot - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
    • setRollerProfile

      public void setRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPositionRot - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
      maxAccelerationRPS2 - maximum acceleration in rotations per second squared
    • setRollerProfile

      public void setRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState)
      Creates a new trapezoidal profile for the roller to follow
      Parameters:
      goalPositionRot - goal position in rotations
      goalVelocityRPS - goal velocity in rotations per second
      maxVelocityRPS - maximum velocity in rotations per second
      maxAccelerationRPS2 - maximum acceleration in rotations per second squared
      setCurrentState - True if the profiles current state should base itself off sensor values rather than continue from the existing state
    • setRollerPower

      public void setRollerPower(double power)
      Sets the power of the primary roller motor
      Parameters:
      power - roller power
    • getRollerPower

      public double getRollerPower()
      Gets the power of the primary roller motor
      Returns:
      roller power
    • getRollerPosition

      public double getRollerPosition()
      Gets the position of the roller in rotations
      Returns:
      roller position in rotations
    • getRollerVelocity

      public double getRollerVelocity()
      Gets the velocity of roller in rotations
      Returns:
      roller velocity
    • setRollerVelocity

      public void setRollerVelocity(double rps, boolean withFF)
      Sets the velocity of the roller in RPS
      Parameters:
      rps - Desired velocity in rotations per second
      withFF - with feedforward
    • isRollerAtTargetSpeed

      public boolean isRollerAtTargetSpeed(double targetSpeed)
      Checks if the roller is at the target speed
      Parameters:
      targetSpeed - target speed in rotations per second
      Returns:
      if roller is at target speed
    • setRollerPowerCmd

      public Command setRollerPowerCmd(double power)
      Command that sets the roller power
      Parameters:
      power - roller power
      Returns:
      instant command to set roller power
    • setRollerRPSCmd

      public Command setRollerRPSCmd(double rps)
      Command that sets the velocity of the roller in rotations per second
      Parameters:
      rps - rotations per second
      Returns:
      instant command to set roller velocity
    • setRollerRPSWithFFCmd

      public Command setRollerRPSWithFFCmd(double rps)
      Command that sets the velocity of the roller in rotations per second with feedforward
      Parameters:
      rps - rotations per second
      Returns:
      instant command to set roller velocity with feedforward
    • startEndRollerPowerCmd

      public Command startEndRollerPowerCmd(double power)
      Command that sets the power of the primary motor (zero if interrupted)
      Parameters:
      power - roller power
      Returns:
      start end command to set roller power
    • startEndRollerRPSCmd

      public Command startEndRollerRPSCmd(double rps)
      Command that sets the velocity of the roller in rotations per second (sets zero power if interrupted)
      Parameters:
      rps - rotations per second
      Returns:
      start end command to set roller velocity
    • startEndRollerRPSWithFFCmd

      public Command startEndRollerRPSWithFFCmd(double rps)
      Command that sets the velocity of the roller in rotations per second with feedforward. (sets zero power if interrupted)
      Parameters:
      rps - rotations per second
      Returns:
      start end command to set roller velocity with feedforward
    • isRollerInTolerance

      public boolean isRollerInTolerance(double lowerBound, double upperBound)
      Bounds checking function that uses the current roller position
      Parameters:
      lowerBound - minimum of acceptable range
      upperBound - maximum of acceptable range
      Returns:
      if the current position is in specified acceptable range
    • holdCurrentPosition

      public void holdCurrentPosition()
      Description copied from class: Microsystem
      Sets the power of the primary motor to zero
      Overrides:
      holdCurrentPosition in class Microsystem
    • getRollerLigaments

      Retrieves ligaments attached to roller Mechanism2d
      Returns:
      roller ligaments