java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
swervelib.simulation.ironmaple.simulation.opponentsim.ManipulatorSim
All Implemented Interfaces:
Sendable, Subsystem

public class ManipulatorSim extends SubsystemBase
  • Constructor Details

    • ManipulatorSim

      public ManipulatorSim()
      Creates a new manipulator simulation.
  • Method Details

    • getIntakeSimulations

      public Map<String,IntakeSimulation> getIntakeSimulations()
      The Map of IntakeSimulation types.
      Returns:
      a Map of IntakeSimulation types.
    • getProjectileSimulations

      public Map<String,Supplier<GamePieceProjectile>> getProjectileSimulations()
      The Map of the GamePieceProjectile types.
      Returns:
      a Map of the GamePieceProjectile types.
    • addIntakeSimulation

      public ManipulatorSim addIntakeSimulation(String intakeName, IntakeSimulation intakeSimulation)
      Adds an intake simulation to the manipulator simulation.
      Parameters:
      intakeName - The name of the intake simulation.
      intakeSimulation - The simulation to add.
      Returns:
      this, for chaining.
    • addProjectileSimulation

      public ManipulatorSim addProjectileSimulation(String projectileName, Supplier<GamePieceProjectile> projectileSimulation)
      Adds a projectile simulation to the manipulator simulation.
      Parameters:
      projectileName - The name of the projectile simulation.
      projectileSimulation - The simulation to add.
      Returns:
      this, for chaining.
    • getIntakeSimulation

      public IntakeSimulation getIntakeSimulation(String intakeName)
      Gets an intake simulation from the manipulator simulation.
      Parameters:
      intakeName - The name of the intake simulation.
      Returns:
      The simulation.
    • getProjectileSimulation

      public Supplier<GamePieceProjectile> getProjectileSimulation(String projectileName)
      Gets a projectile simulation from the manipulator simulation.
      Parameters:
      projectileName - The name of the simulation.
      Returns:
      The simulation.
    • intake

      public Command intake(String intakeName)
      Runs the intake, stops running the intake when the command ends.
      Parameters:
      intakeName -
      Returns:
    • intakeUntilCollected

      public Command intakeUntilCollected(String intakeName)
      Runs intake(String) until the game piece count in the intake goes up.
      Parameters:
      intakeName -
      Returns:
    • score

      public Command score(String projectileName)
      Adds a projectile to the simulation.
      Parameters:
      projectileName - The name of the projectile simulation.
      Returns:
      a command to add the game piece projectile to the simulation.
    • scoreWithIntake

      public Command scoreWithIntake(String intakeName, String projectileName)
      A command that only calls score(String) when there is greater than zero(>0) GamePiece in the intake.
      Parameters:
      intakeName - the intake to check.
      projectileName - the piece to score.
      Returns:
      score(String) when valid.