Class GamePieceProjectile
- Direct Known Subclasses:
NoteOnFly,ReefscapeAlgaeOnFly,ReefscapeCoralOnFly
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
GamePieceOnFieldSimulationupon 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 Summary
FieldsModifier and TypeFieldDescriptionprotected booleanprotected final Rotation3dfinal Stringstatic final doubleThis value may seem unusual compared to the standard 9.8 m/s² for gravity.protected final GamePieceOnFieldSimulation.GamePieceInfoprotected final doubleprotected final Translation2dprotected final Translation2dprotected final doubleprotected final Timer -
Constructor Summary
ConstructorsConstructorDescriptionGamePieceProjectile(GamePieceOnFieldSimulation.GamePieceInfo info, Translation2d initialPosition, Translation2d initialLaunchingVelocityMPS, double initialHeight, double initialVerticalSpeedMPS, Rotation3d gamePieceRotation) Creates a Game Piece Projectile Ejected from a Shooter.GamePieceProjectile(GamePieceOnFieldSimulation.GamePieceInfo info, Translation2d robotPosition, Translation2d shooterPositionOnRobot, ChassisSpeeds chassisSpeedsFieldRelative, Rotation2d shooterFacing, Distance initialHeight, LinearVelocity launchingSpeed, Angle shooterAngle) Creates a Game Piece Projectile Ejected from a Shooter. -
Method Summary
Modifier and TypeMethodDescriptionvoidaddGamePieceAfterTouchGround(SimulatedArena simulatedArena) Adds aGamePieceOnFieldSimulationto aSimulatedArenato Simulate the Game Piece After Touch-Ground.cleanUp()Clean up the trajectory throughprojectileTrajectoryDisplayCallBackHitTargetConfigures the Game Piece Projectile to Disappear Upon Touching Ground.Configures the Game Piece Projectile to Automatically Become aGamePieceOnFieldSimulationUpon Touching Ground.Calculates the Projectile's Current Position.protected Translation3dgetPositionAtTime(double t) Calculates the Projectile's Position at a Given Time.Calculates the Projectile's Velocity at a Given Time.booleanChecks if the Game Piece Has Flown Out of the Field's Boundaries.booleanChecks if the Game Piece Has Touched the Ground.booleanChecks if the Projectile Has Already Hit the Target At the Moment.voidlaunch()Starts the Game Piece Projectile Simulation.static voidupdateGamePieceProjectiles(SimulatedArena simulatedArena, Set<GamePieceProjectile> gamePieceProjectiles) Check everyGamePieceProjectileinstance for available actions.booleanChecks if the projectile will hit the target AT SOME MOMENT during its flightwithHitTargetCallBack(Runnable hitTargetCallBack) Configures a callback to be executed when the game piece hits the target.withProjectileTrajectoryDisplayCallBack(Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBack) Configures a Callback to Display the Trajectory of the Projectile When Launched.withProjectileTrajectoryDisplayCallBack(Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBackHitTarget, Consumer<List<Pose3d>> projectileTrajectoryDisplayCallBackHitTargetMiss) Configures a Callback to Display the Trajectory of the Projectile When Launched.withTargetPosition(Supplier<Translation3d> targetPositionSupplier) Sets a Target for the Game Projectile.withTargetTolerance(Translation3d tolerance) Sets the Target Tolerance for the Game Projectile.withTouchGroundHeight(double heightAsTouchGround) Configures the Height at Which the Projectile Is Considered to Be Touching Ground.
-
Field Details
-
GRAVITY
public static final double GRAVITYThis value may seem unusual compared to the standard 9.8 m/s² for gravity. However, through experimentation, it appears more realistic in our simulation, possibly due to the ignoring of air drag.- See Also:
-
info
-
gamePieceType
-
initialPosition
-
initialLaunchingVelocityMPS
-
initialHeight
protected final double initialHeight -
initialVerticalSpeedMPS
protected final double initialVerticalSpeedMPS -
gamePieceRotation
-
launchedTimer
-
becomesGamePieceOnGroundAfterTouchGround
protected boolean becomesGamePieceOnGroundAfterTouchGround
-
-
Constructor Details
-
GamePieceProjectile
public GamePieceProjectile(GamePieceOnFieldSimulation.GamePieceInfo info, Translation2d robotPosition, Translation2d shooterPositionOnRobot, ChassisSpeeds chassisSpeedsFieldRelative, Rotation2d shooterFacing, Distance initialHeight, LinearVelocity launchingSpeed, Angle shooterAngle) Creates a Game Piece Projectile Ejected from a Shooter.
- Parameters:
info- the info of the game piecerobotPosition- the position of the robot (not the shooter) at the time of launching the game pieceshooterPositionOnRobot- the translation from the shooter's position to the robot's center, in the robot's frame of referencechassisSpeedsFieldRelative- the field-relative velocity of the robot chassis when launching the game piece, influencing the initial velocity of the game pieceshooterFacing- the direction in which the shooter is facing at launchinitialHeight- the initial height of the game piece when launched, i.e., the height of the shooter from the groundlaunchingSpeed- the speed at which the game piece is launcheshooterAngle- the pitch angle of the shooter when launching
-
GamePieceProjectile
public GamePieceProjectile(GamePieceOnFieldSimulation.GamePieceInfo info, Translation2d initialPosition, Translation2d initialLaunchingVelocityMPS, double initialHeight, double initialVerticalSpeedMPS, Rotation3d gamePieceRotation) Creates a Game Piece Projectile Ejected from a Shooter.
- Parameters:
info- the info of the game pieceinitialPosition- the position of the game piece at the moment it is launched into the airinitialLaunchingVelocityMPS- 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 viawithProjectileTrajectoryDisplayCallBack(Consumer). - Starts the
launchedTimer, which stores the amount of time elapsed after the game piece is launched
- Initiates the projectile motion of the game piece. The current pose can be obtained with
-
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.
- Returns:
trueif the game piece has touched the ground, otherwisefalse
-
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).
- Returns:
trueif the game piece has flown out of the field's boundaries, otherwisefalse
-
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 returnfalse.
This is different from
hasHitTarget() - The result is calculated during the
-
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 returnfalse. - This is different from
willHitTarget(), which predicts whether the projectile will eventually hit the target.
- Returns:
trueif the projectile has hit the target at the current time, otherwisefalse
- Before calling
-
cleanUp
Clean up the trajectory through
projectileTrajectoryDisplayCallBackHitTarget- Returns:
- this instance
-
getPositionAtTime
Calculates the Projectile's Position at a Given Time.
This method calculates the position of the projectile using the physics formula for projectile motion.
- Parameters:
t- the time elapsed after the launch of the projectile, in seconds- Returns:
- the calculated position of the projectile at time
tas aTranslation3dobject
-
getPose3d
Calculates the Projectile's Current Position.
The position is calculated using
getPositionAtTime(double)while the rotation is pre-stored.- Returns:
- a
Pose3dobject representing the current pose of the game piece
-
getVelocity3dMPS
Calculates the Projectile's Velocity at a Given Time.
- Returns:
- a
Translation3dobject representing the calculated 3d velocity of the projectile at timet, in meters per second - See Also:
-
getVelocityMPSAtTime(double)
-
addGamePieceAfterTouchGround
Adds a
GamePieceOnFieldSimulationto aSimulatedArenato Simulate the Game Piece After Touch-Ground.The added
GamePieceOnFieldSimulationwill 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
GamePieceOnFieldSimulationwill 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 fromSimulatedArena.getInstance()
-
updateGamePieceProjectiles
public static void updateGamePieceProjectiles(SimulatedArena simulatedArena, Set<GamePieceProjectile> gamePieceProjectiles) Check every
GamePieceProjectileinstance for available actions.1. If a game piece
hasHitTarget(), remove it and runhitTargetCallBackspecified bywithHitTargetCallBack(Runnable)2. If a game piece
hasHitGround(), remove it and create a correspondingGamePieceOnFieldSimulationusingaddGamePieceAfterTouchGround(SimulatedArena)3. If a game piece
hasGoneOutOfField(), remove it. -
enableBecomesGamePieceOnFieldAfterTouchGround
Configures the Game Piece Projectile to Automatically Become a
GamePieceOnFieldSimulationUpon Touching Ground.This method configures the game piece projectile to transform into a
GamePieceOnFieldSimulationwhen it touches the ground.- Returns:
- the current instance of
GamePieceProjectileto allow method chaining
-
disableBecomesGamePieceOnFieldAfterTouchGround
Configures the Game Piece Projectile to Disappear Upon Touching Ground.
Reverts the effect of
enableBecomesGamePieceOnFieldAfterTouchGround(). -
withTargetPosition
Sets a Target for the Game Projectile.
Configures the
targetPositionSupplierof 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 aTranslation3d- Returns:
- the current instance of
GamePieceProjectileto allow method chaining
-
withTargetTolerance
Sets the Target Tolerance for the Game Projectile.
Configures the
tolerancefor 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 aTranslation3d- Returns:
- the current instance of
GamePieceProjectileto allow method chaining
-
withHitTargetCallBack
Configures a callback to be executed when the game piece hits the target.
Sets the
hitTargetCallBackto Execute When the Game Piece Hits the Target.The callback will be triggered when
hasHitTarget()becomestrue.- Parameters:
hitTargetCallBack- the callback to run when the game piece hits the target- Returns:
- the current instance of
GamePieceProjectileto 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
projectileTrajectoryDisplayCallBackHitTargetto be fed with data during thelaunch()method.A
Listcontaining up to 50Pose3dobjects 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 ofPose3dobjects representing the projectile's trajectory- Returns:
- the current instance of
GamePieceProjectileto 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
projectileTrajectoryDisplayCallBackHitTargetto be fed with data during thelaunch()method.A
Listcontaining up to 50Pose3dobjects 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 ofPose3dobjects representing the projectile's trajectory, called if the projectile will hit the target on its pathprojectileTrajectoryDisplayCallBackHitTargetMiss- the callback that will receive the list ofPose3dobjects representing the projectile's trajectory, called if the projectile will be off the target- Returns:
- the current instance of
GamePieceProjectileto allow method chaining
-
withTouchGroundHeight
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
GamePieceOnFieldSimulationusingenableBecomesGamePieceOnFieldAfterTouchGround().- Parameters:
heightAsTouchGround- the height (in meters) at which the projectile is considered to touch the ground- Returns:
- the current instance of
GamePieceProjectileto allow method chaining
-