Class GamePieceProjectile

java.lang.Object
org.ironmaple.simulation.gamepieces.GamePieceProjectile
Direct Known Subclasses:
NoteOnFly

public class GamePieceProjectile extends Object

Simulates a Game Piece Launched into the Air

CheckOnline Documentation

The movement is modeled by simple projectile motion.

If the projectile flies off the field, touches the ground, or hits its target, it will be automatically removed.

Additional Features:

  • Optionally, it can be configured to become a GamePieceOnFieldSimulation upon touching the ground.
  • Optionally, it can be configured to have a "desired target." Upon hitting the target, it can be configured to run a callback.

Limitations:

  • Air drag is ignored.
  • DOES NOT have collision space when flying.
  • Field Details

    • gamePieceType

      public final String gamePieceType
  • Constructor Details

    • GamePieceProjectile

      public GamePieceProjectile(String gamePieceType, Translation2d robotPosition, Translation2d shooterPositionOnRobot, ChassisSpeeds chassisSpeeds, Rotation2d shooterFacing, double initialHeight, double launchingSpeedMPS, double shooterAngleRad)

      Creates a Game Piece Projectile Ejected from a Shooter.

      Parameters:
      gamePieceType - the type of game piece, which will affect the SimulatedArena.getGamePiecesByType(String)
      robotPosition - the position of the robot (not the shooter) at the time of launching the game piece
      shooterPositionOnRobot - the translation from the shooter's position to the robot's center, in the robot's frame of reference
      chassisSpeeds - the velocity of the robot chassis when launching the game piece, influencing the initial velocity of the game piece
      shooterFacing - the direction in which the shooter is facing at launch
      initialHeight - the initial height of the game piece when launched, i.e., the height of the shooter from the ground
      launchingSpeedMPS - the speed at which the game piece is launched, in meters per second (m/s)
      shooterAngleRad - the pitch angle of the shooter when launching, in radians
    • GamePieceProjectile

      public GamePieceProjectile(String gamePieceType, Translation2d initialPosition, Translation2d initialLaunchingVelocityMPS, double initialHeight, double initialVerticalSpeedMPS, Rotation3d gamePieceRotation)

      Creates a Game Piece Projectile Ejected from a Shooter.

      Parameters:
      gamePieceType - the type of game piece, which will affect the SimulatedArena.getGamePiecesByType(String)
      initialPosition - the position of the game piece at the moment it is launched into the air
      initialLaunchingVelocityMPS - the horizontal component of the initial velocity in the X-Y plane, in meters per second (m/s)
      initialHeight - the initial height of the game piece when launched (the height of the shooter from the ground)
      initialVerticalSpeedMPS - the vertical component of the initial velocity, in meters per second (m/s)
      gamePieceRotation - the 3D rotation of the game piece during flight (only affects visualization of the game piece)
  • Method Details

    • launch

      public void launch()

      Starts the Game Piece Projectile Simulation.

      This method initiates the projectile motion of the game piece with the following actions:

      • Initiates the projectile motion of the game piece. The current pose can be obtained with getPose3d().
      • Calculates whether the projectile will hit the target during its flight. The result can be obtained using willHitTarget().
      • Calculates a preview trajectory by simulating the projectile's motion for up to 100 steps, with each step lasting 0.02 seconds.
      • If specified, displays the trajectory using projectileTrajectoryDisplayCallBackHitTarget, which can be set via withProjectileTrajectoryDisplayCallBack(Consumer).
      • Starts the launchedTimer, which stores the amount of time elapsed after the game piece is launched
    • hasHitGround

      public boolean hasHitGround()

      Checks if the Game Piece Has Touched the Ground.

      This method determines whether the game piece has touched the ground at the current time.

      • The result is calculated during the launch() method.
      • Before calling launch(), this method will always return false.
      Returns:
      true if the game piece has touched the ground, otherwise false
    • hasGoneOutOfField

      public boolean hasGoneOutOfField()

      Checks if the Game Piece Has Flown Out of the Field's Boundaries.

      This method determines whether the game piece has flown out of the field's boundaries (outside the fence).

      • The result is calculated during the launch() method.
      • Before calling launch(), this method will always return false.
      Returns:
      true if the game piece has flown out of the field's boundaries, otherwise false
    • willHitTarget

      public boolean willHitTarget()

      Checks if the projectile will hit the target AT SOME MOMENT during its flight

      • The result is calculated during the launch() method.
      • Before calling launch(), this method will always return false.

      This is different from hasHitTarget()

    • hasHitTarget

      public boolean hasHitTarget()

      Checks if the Projectile Has Already Hit the Target At the Moment.

      This method checks whether the projectile has hit the target at the current time.

      • Before calling launch(), this method will always return false.
      • This is different from willHitTarget(), which predicts whether the projectile will eventually hit the target.
      Returns:
      true if the projectile has hit the target at the current time, otherwise false
    • cleanUp

      public GamePieceProjectile cleanUp()

      Clean up the trajectory through projectileTrajectoryDisplayCallBackHitTarget

      Returns:
      this instance
    • getPose3d

      public Pose3d getPose3d()

      Calculates the Projectile's Current Position.

      The position is calculated using getPositionAtTime(double) while the rotation is pre-stored.

      Returns:
      a Pose3d object representing the current pose of the game piece
    • addGamePieceAfterTouchGround

      public void addGamePieceAfterTouchGround(SimulatedArena simulatedArena)

      Adds a GamePieceOnFieldSimulation to a SimulatedArena to Simulate the Game Piece After Touch-Ground.

      The added GamePieceOnFieldSimulation will have the initial velocity of the game piece projectile.

      The game piece will start falling from mid-air until it touches the ground.

      The added GamePieceOnFieldSimulation will always have collision space on the field, even before touching the ground.

      Parameters:
      simulatedArena - the arena simulation to which the game piece will be added, usually obtained from SimulatedArena.getInstance()
    • updateGamePieceProjectiles

      public static void updateGamePieceProjectiles(SimulatedArena simulatedArena, Set<GamePieceProjectile> gamePieceProjectiles)

      Check every GamePieceProjectile instance for available actions.

      1. If a game piece hasHitTarget(), remove it and run hitTargetCallBack specified by withHitTargetCallBack(Runnable)

      2. If a game piece hasHitGround(), remove it and create a corresponding GamePieceOnFieldSimulation using addGamePieceAfterTouchGround(SimulatedArena)

      3. If a game piece hasGoneOutOfField(), remove it.

    • enableBecomesGamePieceOnFieldAfterTouchGround

      public GamePieceProjectile enableBecomesGamePieceOnFieldAfterTouchGround(org.dyn4j.geometry.Convex shape, double gamePieceHeightMeters, double massKg)

      Configures the Game Piece Projectile to Automatically Become a GamePieceOnFieldSimulation Upon Touching Ground.

      This method configures the game piece projectile to transform into a GamePieceOnFieldSimulation when it touches the ground.

      Parameters:
      shape - the shape of the game piece's collision space
      gamePieceHeightMeters - the height (thickness) of the game piece, in meters
      massKg - the mass of the game piece, in kilograms
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • disableBecomesGamePieceOnFieldAfterTouchGround

      public GamePieceProjectile disableBecomesGamePieceOnFieldAfterTouchGround()

      Configures the Game Piece Projectile to Disappear Upon Touching Ground.

      Reverts the effect of enableBecomesGamePieceOnFieldAfterTouchGround(Convex, double, double).

    • withTargetPosition

      public GamePieceProjectile withTargetPosition(Supplier<Translation3d> targetPositionSupplier)

      Sets a Target for the Game Projectile.

      Configures the targetPositionSupplier of this game piece projectile.

      The method launch() will estimate whether or not the game piece will hit the target.

      After calling launch(), hasHitTarget() will indicate whether the game piece has already hit the target.

      Before calling this method, the target position is 0, 0, -100 (x,y,z), which the projectile will never hit.

      Parameters:
      targetPositionSupplier - the position of the target, represented as a Translation3d
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • withTargetTolerance

      public GamePieceProjectile withTargetTolerance(Translation3d tolerance)

      Sets the Target Tolerance for the Game Projectile.

      Configures the tolerance for determining whether the game piece has hit the target. The tolerance defines how close the projectile needs to be to the target for it to be considered a hit.

      If this method is not called, the default tolerance is 0.2, 0.2, 0.2 (x,y,z)

      Parameters:
      tolerance - the tolerance for the target, represented as a Translation3d
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • withHitTargetCallBack

      public GamePieceProjectile withHitTargetCallBack(Runnable hitTargetCallBack)

      Configures a callback to be executed when the game piece hits the target.

      Sets the hitTargetCallBack to Execute When the Game Piece Hits the Target.

      The callback will be triggered when hasHitTarget() becomes true.

      Parameters:
      hitTargetCallBack - the callback to run when the game piece hits the target
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • withProjectileTrajectoryDisplayCallBack

      public GamePieceProjectile withProjectileTrajectoryDisplayCallBack(Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBack)

      Configures a Callback to Display the Trajectory of the Projectile When Launched.

      Sets the projectileTrajectoryDisplayCallBackHitTarget to be fed with data during the launch() method.

      A List containing up to 50 Pose3d objects will be passed to the callback, representing the future trajectory of the projectile.

      This is usually for visualizing the trajectory of the projectile on a telemetry, like Advantage Scope

      Parameters:
      projectileTrajectoryDisplayCallBack - the callback that will receive the list of Pose3d objects representing the projectile's trajectory
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • withProjectileTrajectoryDisplayCallBack

      public GamePieceProjectile withProjectileTrajectoryDisplayCallBack(Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBackHitTarget, Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBackHitTargetMiss)

      Configures a Callback to Display the Trajectory of the Projectile When Launched.

      Sets the projectileTrajectoryDisplayCallBackHitTarget to be fed with data during the launch() method.

      A List containing up to 50 Pose3d objects will be passed to the callback, representing the future trajectory of the projectile.

      This is usually for visualizing the trajectory of the projectile on a telemetry, like Advantage Scope

      Parameters:
      projectileTrajectoryDisplayCallBackHitTarget - the callback that will receive the list of Pose3d objects representing the projectile's trajectory, called if the projectile will hit the target on its path
      projectileTrajectoryDisplayCallBackHitTargetMiss - the callback that will receive the list of Pose3d objects representing the projectile's trajectory, called if the projectile will be off the target
      Returns:
      the current instance of GamePieceProjectile to allow method chaining
    • withTouchGroundHeight

      public GamePieceProjectile withTouchGroundHeight(double heightAsTouchGround)

      Configures the Height at Which the Projectile Is Considered to Be Touching Ground.

      Sets the heightAsTouchGround, defining the height at which the projectile is considered to have landed.

      When the game piece is below this height, it will either be deleted or, if configured, transformed into a GamePieceOnFieldSimulation using enableBecomesGamePieceOnFieldAfterTouchGround(Convex, double, double).

      Parameters:
      heightAsTouchGround - the height (in meters) at which the projectile is considered to touch the ground
      Returns:
      the current instance of GamePieceProjectile to allow method chaining