Class IntakeSimulation

java.lang.Object
org.dyn4j.collision.Fixture
org.dyn4j.dynamics.BodyFixture
org.ironmaple.simulation.IntakeSimulation
All Implemented Interfaces:
org.dyn4j.DataContainer

public class IntakeSimulation extends org.dyn4j.dynamics.BodyFixture

Simulates an Intake Mechanism on the Robot.

CheckOnline Documentation

The intake is a 2D component attached to one side of the robot's chassis. It is rectangular in shape and extends from the robot when activated.

The intake can be turned on through startIntake(), which causes it to extend, expanding the collision space of the robot's chassis. When turned off via stopIntake(), the intake retracts.

The intake can "collect" GamePieceOnFieldSimulation instances from the field, removing them and incrementing the gamePiecesInIntakeCount.

A game piece is collected if the following conditions are met:

Note: This class simulates an idealized "touch it, get it" intake and does not model the actual functioning of an intake mechanism.

  • Constructor Details

    • IntakeSimulation

      public IntakeSimulation(String targetedGamePieceType, AbstractDriveTrainSimulation driveTrainSimulation, org.dyn4j.geometry.Convex shape, int capacity)

      Creates an Intake Simulation with a Specific Shape.

      This constructor initializes an intake with a custom shape that is used when the intake is fully extended.

      Parameters:
      targetedGamePieceType - the type of game pieces that this intake can collect
      driveTrainSimulation - the chassis to which this intake is attached
      shape - the shape of the intake when fully extended, represented as a Convex object
      capacity - the maximum number of game pieces that the intake can hold
  • Method Details

    • InTheFrameIntake

      public static IntakeSimulation InTheFrameIntake(String targetedGamePieceType, AbstractDriveTrainSimulation driveTrainSimulation, Distance width, IntakeSimulation.IntakeSide side, int capacity)

      Creates an Intake Simulation that Tightly Attaches to One Side of the Chassis.

      This typically represents an In-The-Frame (ITF) Intake.

      Parameters:
      targetedGamePieceType - the type of game pieces that this intake can collect
      driveTrainSimulation - the chassis to which this intake is attached
      width - the width of the intake
      side - the side of the chassis where the intake is attached
      capacity - the maximum number of game pieces that the intake can hold
    • OverTheBumperIntake

      public static IntakeSimulation OverTheBumperIntake(String targetedGamePieceType, AbstractDriveTrainSimulation driveTrainSimulation, Distance width, Distance lengthExtended, IntakeSimulation.IntakeSide side, int capacity)

      Creates an Intake Simulation that Extends Out of the Chassis Frame.

      This typically represents an Over-The-Bumper (OTB) Intake.

      Parameters:
      targetedGamePieceType - the type of game pieces that this intake can collect
      driveTrainSimulation - the chassis to which this intake is attached
      width - the valid width of the intake
      lengthExtended - the length the intake extends out from the chassis when activated
      side - the side of the chassis where the intake is attached
      capacity - the maximum number of game pieces that the intake can hold
      Returns:
      a new instance of IntakeSimulation that extends over the bumper
    • startIntake

      public void startIntake()

      Turns the Intake On.

      Extends the intake out from the chassis, making it part of the chassis's collision space.

      Once activated, the intake is considered running and will listen for contact with GamePieceOnFieldSimulation instances, allowing it to collect game pieces.

    • stopIntake

      public void stopIntake()

      Turns the Intake Off.

      Retracts the intake into the chassis, removing it from the chassis's collision space.

      Once turned off, the intake will no longer listen for or respond to contacts with GamePieceOnFieldSimulation instances.

    • getGamePiecesAmount

      public int getGamePiecesAmount()

      Get the amount of game pieces in the intake.

      Returns:
      the amount of game pieces stored in the intake
    • obtainGamePieceFromIntake

      public boolean obtainGamePieceFromIntake()

      Removes 1 game piece from the intake.

      Deducts the getGamePiecesAmount()} by 1, if there is any remaining.

      This is used to obtain a game piece from the intake and move it a feeder/shooter.

      Returns:
      if there is game piece(s) remaining, and therefore retrieved
    • addGamePieceToIntake

      public boolean addGamePieceToIntake()

      Adds 1 game piece from the intake.

      Increases the getGamePiecesAmount()} by 1, if there is still space.

      Returns:
      if there is still space in the intake to perform this action
    • setGamePiecesCount

      public int setGamePiecesCount(int gamePiecesInIntakeCount)

      Sets the amount of game pieces in the intake.

      Sets the getGamePiecesAmount()} to a given amount.

      Will make sure that the amount is non-negative and does not exceed the capacity

      Returns:
      the actual (clamped) game piece count after performing this action
    • getGamePieceContactListener

      public IntakeSimulation.GamePieceContactListener getGamePieceContactListener()

      Obtains a New Instance of the IntakeSimulation.GamePieceContactListener for This Intake.

      Returns:
      a new IntakeSimulation.GamePieceContactListener for this intake
    • removeObtainedGamePieces

      public void removeObtainedGamePieces(SimulatedArena arena)

      Clears the game pieces that have been obtained by the intake.

      This method is called from SimulatedArena.simulationPeriodic() to remove the GamePieceOnFieldSimulation instances that have been obtained by the intake from the field.

      Game pieces are marked for removal if they have come into contact with the intake during the last SimulatedArena.getSimulationSubTicksIn1Period() sub-ticks. These game pieces should be removed from the field to reflect their interaction with the intake.

    • register

      public void register()
    • register

      public void register(SimulatedArena arena)