Class SimulatedArena
- Direct Known Subclasses:
Arena2024Crescendo,Arena2025Reefscape
Abstract Simulation World
Check Online Documentation
The heart of the simulator.
This class cannot be instantiated directly; it must be created as a specific season's arena.
The default instance can be obtained using the getInstance() method.
Simulates all interactions within the arena field.
The following objects can be added to the simulation world and will interact with each other:
AbstractDriveTrainSimulation: Represents abstract drivetrain simulations with collision detection.GamePieceOnFieldSimulation: Represents abstract game pieces with collision detection.IntakeSimulation: Represents an intake simulation that responds to contact withGamePieceOnFieldSimulation.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classRepresents an Abstract Field Mapstatic interfaceRepresents a custom simulation to be updated during each simulation sub-tick. -
Field Summary
FieldsModifier and TypeFieldDescriptionstatic booleanWhether to allow the simulation to run a real robot This feature is HIGHLY RECOMMENDED to be turned OFFprotected final List<SimulatedArena.Simulatable>protected final Set<AbstractDriveTrainSimulation>protected final Set<GamePieceProjectile>protected final Set<GamePieceOnFieldSimulation>protected final org.dyn4j.world.World<org.dyn4j.dynamics.Body> -
Constructor Summary
ConstructorsModifierConstructorDescriptionprotectedSimulatedArena(SimulatedArena.FieldMap obstaclesMap) Constructs a new simulation arena with the specified field map of obstacles. -
Method Summary
Modifier and TypeMethodDescriptionvoidaddCustomSimulation(SimulatedArena.Simulatable simulatable) Registers a custom simulation.voidaddDriveTrainSimulation(AbstractDriveTrainSimulation driveTrainSimulation) Registers anAbstractDriveTrainSimulation.voidaddGamePiece(GamePieceOnFieldSimulation gamePiece) Registers aGamePieceOnFieldSimulationto the Simulation.voidaddGamePieceProjectile(GamePieceProjectile gamePieceProjectile) Registers aGamePieceProjectileto the Simulation and Launches It.protected voidaddIntakeSimulation(IntakeSimulation intakeSimulation) Registers anIntakeSimulation.voidRemoves AllGamePieceOnFieldSimulationObjects from the Simulation.Pose3d[]Obtains the 3D Poses of a Specific Type of Game Piece as an array.getGamePiecesByType(String type) Obtains the 3D Poses of a Specific Type of Game Piece.static SimulatedArenaGets/Creates the Default Simulation Worldstatic Timestatic intstatic voidoverrideInstance(SimulatedArena newInstance) Overrides the Default Simulation Worldstatic voidoverrideSimulationTimings(Time robotPeriod, int simulationSubTicksPerPeriod) Overrides the Timing Configurations of the Simulations.abstract voidPlaces Game Pieces on the Field for Autonomous Mode.booleanremoveGamePiece(GamePieceOnFieldSimulation gamePiece) Removes aGamePieceOnFieldSimulationfrom the Simulation.booleanremoveProjectile(GamePieceProjectile gamePieceLaunched) Removes aGamePieceProjectilefrom the Simulation.voidResets the Field for Autonomous Mode.voidUpdate the simulation world.
-
Field Details
-
ALLOW_CREATION_ON_REAL_ROBOT
public static boolean ALLOW_CREATION_ON_REAL_ROBOTWhether to allow the simulation to run a real robot This feature is HIGHLY RECOMMENDED to be turned OFF -
physicsWorld
protected final org.dyn4j.world.World<org.dyn4j.dynamics.Body> physicsWorld -
driveTrainSimulations
-
gamePiecesOnField
-
gamePiecesLaunched
-
customSimulations
-
-
Constructor Details
-
SimulatedArena
Constructs a new simulation arena with the specified field map of obstacles.
This constructor initializes a physics world with zero gravity and adds the provided obstacles to the world.
It also sets up the collections for drivetrain simulations, game pieces, projectiles, and intake simulations.
- Parameters:
obstaclesMap- the season-specific field map containing the layout of obstacles for the simulation
-
-
Method Details
-
getInstance
Gets/Creates the Default Simulation World
Multiple instances of
SimulatedArenacan exist elsewhere.- Returns:
- the main simulation arena instance
- Throws:
IllegalStateException- if the method is call when running on a real robot
-
overrideInstance
Overrides the Default Simulation World
Overrides the return value of
getInstance()This method allows simulating an arena from a different year or a custom field.
Currently, only the 2024 arena is supported, so avoid calling this method for now.
- Parameters:
newInstance- the new simulation arena instance to override the current one
-
getSimulationSubTicksIn1Period
public static int getSimulationSubTicksIn1Period() -
getSimulationDt
-
overrideSimulationTimings
Overrides the Timing Configurations of the Simulations.
If Using Advantage-Kit: DO NOT CHANGE THE DEFAULT TIMINGS
Changes apply to every instance of
SimulatedArena.The new configuration will take effect the next time
simulationPeriodic()is called on an instance.It is recommended to call this method before the first call to
simulationPeriodic()of any instance.It is also recommended to keep the simulation frequency above 200 Hz for accurate simulation results.
- Parameters:
robotPeriod- the time between two calls ofsimulationPeriodic(), usually obtained fromIterativeRobotBase.getPeriod()simulationSubTicksPerPeriod- the number of Iterations, orsimulationSubTick(int)that the simulation runs per each call tosimulationPeriodic()
-
addCustomSimulation
Registers a custom simulation.
- Parameters:
simulatable- the custom simulation to register
-
addIntakeSimulation
Registers an
IntakeSimulation.NOTE: This method is automatically called in the constructor of
IntakeSimulation, so you don't need to call it manually.The intake simulation should be bound to an
AbstractDriveTrainSimulationand becomes part of its collision space.This method immediately starts the
IntakeSimulation.GamePieceContactListener, which listens for contact between the intake and any game piece.- Parameters:
intakeSimulation- the intake simulation to be registered
-
addDriveTrainSimulation
Registers an
AbstractDriveTrainSimulation.The collision space of the drive train is immediately added to the simulation world.
Starting from the next call to
simulationPeriodic(), theAbstractDriveTrainSimulation.simulationSubTick()method will be called during each sub-tick of the simulator.- Parameters:
driveTrainSimulation- the drivetrain simulation to be registered
-
addGamePiece
Registers a
GamePieceOnFieldSimulationto the Simulation.The collision space of the game piece is immediately added to the simulation world.
IntakeSimulations will be able to interact with this game piece during the next call tosimulationPeriodic().- Parameters:
gamePiece- the game piece to be registered in the simulation
-
addGamePieceProjectile
Registers a
GamePieceProjectileto the Simulation and Launches It.Calls to
GamePieceProjectile.launch(), which will launch the game piece immediately.- Parameters:
gamePieceProjectile- the projectile to be registered and launched in the simulation
-
removeGamePiece
Removes a
GamePieceOnFieldSimulationfrom the Simulation.Removes the game piece from the physics world and the simulation's game piece collection.
- Parameters:
gamePiece- the game piece to be removed from the simulation- Returns:
trueif this set contained the specified element
-
removeProjectile
Removes a
GamePieceProjectilefrom the Simulation.Removes the game piece projectile from the simulation.
- Parameters:
gamePieceLaunched- the game piece projectile to be removed from the simulation- Returns:
trueif this set contained the specified element
-
clearGamePieces
public void clearGamePieces()Removes All
GamePieceOnFieldSimulationObjects from the Simulation.This method clears all game pieces from the physics world and the simulation's game piece collection.
-
simulationPeriodic
public void simulationPeriodic()Update the simulation world.
This method should be called ONCE in
IterativeRobotBase.simulationPeriodic()(orLoggedRobot.simulationPeriodic()if using Advantage-Kit)If not configured through
overrideSimulationTimings(Time, int), the simulator will iterate through 5 Sub-ticks by default.The amount of CPU Time that the Dyn4j engine uses in displayed in
SmartDashboard/MapleArenaSimulation/Dyn4jEngineCPUTimeMS, usually performance is not a concern -
gamePiecesOnField
-
gamePieceLaunched
-
getGamePiecesByType
Obtains the 3D Poses of a Specific Type of Game Piece.
This method is used to visualize the positions of game pieces
Also, if you have a game-piece detection vision system (wow!), this is the how you can simulate it.
Both
GamePieceOnFieldSimulationandGamePieceProjectileof the specified type will be included.- The type is determined in the constructor of
GamePieceOnFieldSimulation. - For example,
CrescendoNoteOnFieldhas the type "Note".
- Parameters:
type- the type of game piece, as determined by the constructor ofGamePieceOnFieldSimulation- Returns:
- a
ListofPose3dobjects representing the 3D positions of the game pieces
- The type is determined in the constructor of
-
getGamePiecesArrayByType
Obtains the 3D Poses of a Specific Type of Game Piece as an array.
- See Also:
-
resetFieldForAuto
public void resetFieldForAuto()Resets the Field for Autonomous Mode.
This method clears all current game pieces from the field and places new game pieces in their starting positions for the autonomous mode.
-
placeGamePiecesOnField
public abstract void placeGamePiecesOnField()Places Game Pieces on the Field for Autonomous Mode.
This method sets up the game pieces on the field, typically in their starting positions for autonomous mode.
It should be implemented differently for each season-specific subclass of
SimulatedArenato reflect the unique game piece placements for that season's game.
-