Simulation Architecture
Core Principle
Reusable code goes in sim-core. Game-specific code goes under that year’s robot project.
The simulator runs the same Robot.java and subsystem code that deploys to the real robot. Instead of talking to real motors and sensors, the code talks to simulated physics engines.
This is not a video game. It uses the same physics equations (Newton’s laws, motor curves, friction models) that govern the real robot.
Two Layers
| Layer | Location | Scope |
|---|---|---|
| sim-core | robot/sim-core/ | Reusable physics: rigid bodies, collisions, game pieces, field geometry, scoring, telemetry, vision |
| Year-specific | e.g. robot/2026-rebuilt/src/main/java/frc/robot/sim/ | Field layout, robot config, mechanism bridges |
When a new game drops, you only write the year-specific layer. Everything else is inherited.
Simulation was introduced in 2025 (Reefscape) and significantly expanded for 2026 (REBUILT).
Dual-Engine Architecture
The sim pairs two physics engines, each handling what it does best:
Your Robot Code
(Robot.java, subsystems, commands)
|
| motor voltages, sensor reads
v
+-----------+-----------+
| |
v v
MapleSim sim-core (ODE4J)
(Drivetrain) (Everything Else)
| |
| pose, velocity | collisions, intake,
| encoders, gyro | scoring, terrain, vision
| |
v v
Year-Specific SimManager (orchestrator)
|
v
AdvantageKit → AdvantageScopeMapleSim (Drivetrain)
MapleSim is purpose-built for FRC swerve simulation:
- Motor models (voltage → torque, with current limits)
- Tire dynamics (slip, traction, carpet friction)
- Gear ratios (drive and steer reductions)
- Encoder/gyro feedback (TalonFX + Pigeon2 sim state)
ODE4J via sim-core (Everything Else)
ODE4J handles general rigid body physics:
- Hundreds of game pieces with gravity, bounce, and collisions
- 3D field geometry (walls, ramps, bumps) from OBJ meshes
- Intake zones, launch trajectories, scoring detection
- Vision simulation (Limelight AprilTag estimates + game piece detection via frustum sensors)
Why Two Engines?
| Concern | MapleSim | ODE4J (sim-core) |
|---|---|---|
| Swerve motor physics | Built for it | Not designed for FRC motors |
| Tire slip / traction | Realistic carpet model | Generic friction |
| Encoder / gyro sim | Direct CTRE integration | No hardware API |
| Rigid body collisions | Not supported | Excellent |
| Hundreds of game pieces | Not supported | Optimized (sleep/wake) |
| 3D terrain (ramps) | 2D only | Full 3D mesh collision |
MapleSim owns the robot’s position and velocity. ODE4J is a kinematic follower — it mirrors MapleSim’s pose so game pieces can collide with the robot, but it never drives the robot. Don’t try to drive from both engines.
Key design decision: MapleSim’s arena is configured with AddRampCollider=false — MapleSim only handles the hub collision boundary (2D). ODE4J handles all 3D terrain including ramps.
sim-core Internals
Located at robot/sim-core/src/main/java/frc/sim/:
Packages
| Package | Purpose |
|---|---|
frc.sim.core | Physics world, field geometry, terrain surfaces, math utils |
frc.sim.chassis | Chassis rigid body, swerve module model, config |
frc.sim.gamepiece | Game pieces, intake zones, launch parameters, manager, ShooterSim bridge |
frc.sim.motor | Reusable CTRE TalonFX sim wrappers (SimMotor, TalonFXMotorSim, TalonFXArmSim, BatterySimUtil) |
frc.sim.scoring | Score tracking via sensor zones |
frc.sim.telemetry | NT publishing, ground clearance |
frc.sim.vision | Limelight simulation, camera configs |
Key Classes
| Class | Purpose |
|---|---|
PhysicsWorld | ODE4J world wrapper. Gravity, ground plane, adaptive sub-stepping, terrain surfaces. |
FieldGeometry | Loads OBJ meshes as collision surfaces (walls, ramps, field elements). |
TerrainSurface | Contact material presets: CARPET, WALL, RUBBER, POLYCARBONATE. |
ChassisSimulation | Robot rigid body. Three modes: velocity-follow, force-based, standalone motor model. |
GamePieceManager | Manages all pieces: spawn, intake (counter-based), launch, proximity sleep/wake. |
IntakeZone | Robot-relative bounding box for detecting game piece overlap. |
LaunchParameters | 3D launch velocity from hood angle + heading + robot velocity. |
ScoringTracker | Detects pieces passing through scoring sensor zones. |
SimTelemetry | Publishes sim data to AdvantageKit. |
VisionSimManager | Simulates Limelight cameras via NetworkTables. |
LimelightSim | Per-camera simulation. AprilTag mode: FPS throttling, latency lookback, pose history. Game piece mode: builds a trimesh frustum sensor, publishes tv/tx/ty/ta to NT. |
Adaptive Sub-stepping
Fast objects (e.g., a ball at 30 m/s) can tunnel through thin walls in a single 20ms step. PhysicsWorld.step() detects the fastest body and subdivides the timestep so no object moves more than 0.1m per sub-step. Most frames use 1 sub-step; extra sub-steps only kick in during launches.
Proximity Sleep/Wake
With hundreds of game pieces, simulating every one is expensive. GamePieceManager uses a chunk-based 2×2m grid system:
- Game pieces are assigned to chunks based on their position
- Only chunks within a certain radius of the robot are kept active
- A hysteresis gap (wake radius < sleep radius) prevents thrashing at the boundary
Known bug: The chunk-based system can occasionally let balls tunnel through surfaces when a ball moves across a chunk boundary in a single physics step. This will be fixed in a future update. If you see balls passing through walls, this is likely the cause.
The older approach used a simple radius hysteresis: wake pieces within 1.5m, sleep beyond 3.0m. The current chunk system replaces this but follows the same principle. See the constants at the top of RebuiltSimManager.java for the current proximity radii.
Terrain Surfaces
Four built-in contact materials:
| Surface | Friction | Bounce | Notes |
|---|---|---|---|
| CARPET | High | Low | Soft contacts, prevents ball jitter |
| WALL | Medium | Medium | Hard contacts |
| RUBBER | High | Medium | — |
| POLYCARBONATE | Low | Medium | — |
Per-geom overrides let you assign different materials to different field elements.
Sensor Geoms (Scoring)
Scoring zones use ODE4J sensors — they detect overlap without creating contact joints. Pieces pass through the trigger while the system records the score.
Chassis Control Modes
| Mode | Method | Use Case |
|---|---|---|
| Velocity-follow | setVelocity() | Kinematic follower for MapleSim. Applies corrective forces F = m * (v_desired - v_current) / dt. ODE4J still handles Z/pitch/roll from terrain. |
| Force-based | applyForces() | Apply world-frame forces directly. |
| Standalone | SwerveModuleSim | DC motor voltage-to-force model, for running without MapleSim. |
Game Piece Lifecycle
This is the same regardless of game year:
SPAWN → Created on field by year-specific layout
↓
DISABLED → Moved underground, zero physics cost
↓ (robot within wake radius)
AWAKE → Physics enabled
↓ (overlaps intake zone + intake active)
CONSUMED → Removed from world, hopper counter increments
↓ (mechanism fires, cooldown expired, hopper > 0)
LAUNCHED → New body spawned at mechanism exit with 3D velocity
↓ (gravity, bounces off walls/field)
IN FLIGHT → Normal rigid body physics
↓ (enters scoring sensor zone)
SCORED → Removed from field, score incrementsCounter-based tracking: GamePieceManager tracks held pieces with heldCount / maxCapacity. intakePiece() removes from world + increments counter. launchPiece() decrements counter + spawns new physics body. Pieces are grouped by type in a Map<String, List<GamePiece>>.
Vision Simulation
frc.sim.vision provides Limelight camera simulation in two modes:
VisionSimManager— manages multiple simulated cameras (AprilTag and game piece), maintains a 2-second pose history buffer, and coordinates game piece sensor enable/disable around the physics stepLimelightSim— per-camera simulation supporting two modes (see below)CameraConfig/LimelightType— hardware profiles (LL3: 30fps / 25ms latency, LL4: 60fps / 20ms latency)
AprilTag Mode
Each tick, the robot’s true pose is recorded into a TimeInterpolatableBuffer. When a camera “captures a frame” (based on its FPS), it samples the pose at now - latency to simulate realistic measurement delay. Results are published to NetworkTables in YALL/PoseEstimate format with fake fiducial data (4 tags, tuned for tight stddevs).
Current status: Reports exact robot pose with fake AprilTag metadata (constant number of detections). Good enough for testing pose-estimation pipelines but doesn’t model tag visibility or measurement noise.
Planned: Real tag visibility based on camera FOV and distance, with distance-based noise.
Game Piece Mode
A LimelightSim in game piece mode builds a 3D trimesh frustum (from the camera’s FOV, near plane, and far plane) and attaches it to the chassis body as an ODE4J sensor. The frustum follows the robot automatically since it’s attached to the chassis rigid body.
Detection pipeline:
prepareGamePiece()— enable/disable the frustum sensor based on FPS gating (called before physics step)- ODE4J collision detection runs — the frustum detects overlapping game piece bodies
updateGamePiece()— reads sensor contacts, finds the closest piece, converts its 3D position to camera-relative angles, and publishestv/tx/ty/tato NetworkTables (called after physics step)
The published NT entries are consumed by LimelightHelpers.getTV/getTX/getTY/getTA, so subsystem code (e.g. IntakeSubsystem) reads the same API in sim and on the real robot.
Motor Controller Adapters
The year-specific SimManager bridges MapleSim to CTRE’s simulation APIs with bidirectional adapters:
MapleSim → (position, velocity) → Adapter → TalonFX SimState
MapleSim ← (commanded voltage) ← Adapter ← TalonFX SimStateTwo adapter types in 2026’s RebuiltSimManager:
TalonFXMotorControllerSim— syncs a single TalonFX motorTalonFXMotorControllerWithRemoteCanCoderSim— syncs TalonFX rotor state AND CANcoder absolute position (used for swerve steer modules)
Both connect to SimulatedBattery for brownout effects.
Motor-Based Mechanism Simulation
All six non-drivetrain motors are simulated in RebuiltSimManager using WPILib’s built-in physics sim classes, not state-enum reads:
| Mechanism | WPILib Sim Class | What it models |
|---|---|---|
| Shooter wheels | DCMotorSim | Motor voltage → angular position and velocity |
| Shooter hood | SingleJointedArmSim | Motor voltage → arm angle, with gravity and hard angle limits |
| Feeder | DCMotorSim | Motor voltage → angular position and velocity |
| Spindexer | DCMotorSim | Motor voltage → angular position and velocity |
| Intake deploy | DCMotorSim | Motor voltage → angular position and velocity |
| Intake roller | DCMotorSim | Motor voltage → angular position and velocity |
The frc.sim.motor Package
The repetitive CTRE “read voltage → step physics → write encoder back” pattern is encapsulated in reusable wrappers under robot/sim-core/src/main/java/frc/sim/motor/:
| Class | Purpose |
|---|---|
SimMotor | Interface — update(dt) steps one motor sim tick (supply voltage in, physics step, encoder writeback). |
TalonFXMotorSim | Wraps a DCMotorSim + TalonFXSimState and implements SimMotor. Handles gear ratio and inversion. |
TalonFXArmSim | Same as above, but wraps a SingleJointedArmSim for arm mechanisms (hood). |
BatterySimUtil | updateBatteryVoltage(motors...) aggregates current draws and writes RoboRioSim.setVInVoltage(). Call first each tick so setInputVoltage sees the correct clamp. |
Inside RebuiltSimManager, the per-motor block is now a one-liner motor.update(DT) plus a single BatterySimUtil.updateBatteryVoltage(...) call at the top of the tick. The previous inline 5-step per-motor wiring was consolidated — the class shrank by roughly 100 lines.
The wiring pattern each wrapper performs (hidden from the orchestrator):
talonFXSimState.setSupplyVoltage(batteryVoltage)physicsSim.setInputVoltage(voltage)— with inversion appliedphysicsSim.update(DT)talonFXSimState.setRawRotorPosition(gearRatio * sim position)— with inversion appliedtalonFXSimState.setRotorVelocity(gearRatio * sim velocity)— with inversion applied
This closes the loop: robot code commands a motor → CTRE writes the voltage → sim computes physics → sim writes encoder feedback → robot code reads the encoder.
Motor inversion convention: WPILib sims use CCW-positive convention. CTRE TalonFXSimState reports voltage and expects position/velocity in the motor’s configured positive direction.
- 4 motors are
Clockwise_Positive(shooter, feeder, spindexer, and the hood mechanically): voltage must be negated before passing to the WPILib sim, and position/velocity from the sim must be negated before writing back to CTRE. - Hood exception: The hood is
Clockwise_Positivein CTRE config, but CW motor rotation physically increases the arm angle — which aligns with SingleJointedArmSim’s CCW-positive convention. So the hood uses no negation on either input or writeback. - 2 intake motors are
CounterClockwise_Positive(default, no inversion config): pass voltage through directly, no negation in either direction.
The inversion flag is passed once into each TalonFXMotorSim / TalonFXArmSim at construction; the wrapper applies it consistently on input and writeback.
Subsystem sim accessor pattern: Subsystems expose their TalonFXSimState (and any other sim-only handles) via accessor methods below a clearly delimited line. Real-robot methods live above the line, sim-only methods below, and sim-only methods always carry Sim in their name:
// ==================== SIMULATION SUPPORT — sim-only methods below this line ====================
public com.ctre.phoenix6.sim.TalonFXSimState getDeployMotorSimState() {
return motor.getSimState();
}RebuiltSimManager caches these states in its constructor and wraps each one in a TalonFXMotorSim / TalonFXArmSim. No subsystem owns or steps a DCMotorSim — that all lives in RebuiltSimManager. Subsystems expose only the state handle; RebuiltSimManager does the physics.
Battery simulation: BatterySimUtil.updateBatteryVoltage(...) wraps BatterySim.calculateDefaultBatteryLoadedVoltage() and aggregates current draws from all six motors each tick (shooter counted ×4 for leader + 3 followers). It writes RoboRioSim.setVInVoltage() first so setInputVoltage’s internal voltage clamp uses the correct value.
See the motor physics constants (SHOOTER_MOI, HOOD_GEAR_RATIO, etc.) at the top of RebuiltSimManager.java for the current tuning values.
Component Animation
The SimManager drives mechanism animation from live motor sim readings — no separate angle accumulators. Each tick, the roller, spindexer, feeder, and shooter angles are read directly from the corresponding DCMotorSim.getAngularPositionRotations(). The hood angle comes directly from SingleJointedArmSim.getAngleRads() — it reflects real physics, including gravity droop.
These are published as an array of Pose3d values to AdvantageKit, which AdvantageScope renders as articulated robot parts. Array index order must match the model_N.glb files listed in the AdvantageScope config.
3D Models & Git LFS
AdvantageScope can render the actual robot CAD in its 3D view using GLB (binary glTF) model files. These files live in sim_models/ inside each year’s robot project.
Directory Structure
robot/2026-rebuilt/sim_models/
├── Robot_Components/ # Articulated model (individual components)
│ ├── config.json # AdvantageScope config (maps components to GLB files)
│ ├── model.glb # Base chassis
│ └── model_0.glb ... model_15.glb # Individual mechanism parts
└── Robot_Static/ # Single-mesh model (no moving parts)
├── config.json
└── model.glbGit LFS (Large File Storage)
GLB files are binary and can be large (the 2026 models total ~100MB). To keep the repo lean:
- GLB files are stored via Git LFS — the
.gitattributesat the repo root routes all*.glbfiles through LFS automatically - Models are excluded from clone — the
.lfsconfigat the repo root setsfetchexclude = **/sim_models/**, so cloning the repo downloads tiny pointer files (~130 bytes) instead of the real models - Models download on demand — each year’s
build.gradlehas afetchModelstask that pulls only that year’s models viagit lfs pull config.jsonis NOT in LFS — it’s a small JSON file tracked normally by git, always available on clone
How It Works for Developers
From a developer’s perspective, this is invisible:
- Adding models: Just
git add/git commityour GLB files. LFS handles the rest behind the scenes. - Getting models: Run
./gradlew simulateJava— thefetchModelstask runs automatically and downloads any missing models. You can also run./gradlew fetchModelsdirectly. - Skipping model download: Pass
-PskipFetchModelsto skip the download (e.g../gradlew simulateJava -PskipFetchModels). - No LFS installed? The build still works. You just won’t see the robot model in AdvantageScope. The Gradle task prints install instructions.
Git LFS is included by default with Git for Windows. On macOS/Linux, install it separately — see the Troubleshooting section in the Quick Start guide.
New Year Setup
When creating a new year’s robot project from the template:
- The
fetchModelsGradle task is already included in the template’sbuild.gradle - The
sim_models/Robot_Components/andsim_models/Robot_Static/directories exist with placeholderconfig.jsonfiles - Export your CAD as GLB files into the appropriate folder —
Robot_Components/for articulated models (separate mechanism parts) andRobot_Static/for a single static mesh - Update the
config.jsonfiles with your component rotations and positions - Commit and push — LFS tracks the GLB files automatically
2026 REBUILT Specifics
Code: robot/2026-rebuilt/src/main/java/frc/robot/sim/
| Class | Purpose |
|---|---|
RebuiltSimManager | Orchestrator. Sim loop at 50Hz. Bridges MapleSim ↔ ODE4J. Uses frc.sim.motor wrappers to keep the motor-update block compact. |
RebuiltField | Field layout: hubs, ramps, scoring zones, fuel spawn positions. Loads field_collision.obj. |
RebuiltGamePieces | Fuel ball config: sphere, radius and mass defined in class constants. |
ShooterSim — the bridge that launches a game piece when the shooter fires — previously lived under frc.robot.sim. It has been moved to robot/sim-core/src/main/java/frc/sim/gamepiece/ShooterSim.java since nothing about it is game-specific; it still takes DoubleSuppliers for live hood angle and launch velocity so the year-specific layer wires it up with the 2026 shooter.
Mechanism simulation approach: All six non-drivetrain motors (shooter wheels, hood, feeder, spindexer, intake deploy, intake roller) are simulated in RebuiltSimManager using DCMotorSim or SingleJointedArmSim. No subsystem overrides simulationPeriodic() — all motor physics live in the orchestrator. Subsystems expose their TalonFXSimState via accessor methods so RebuiltSimManager can read voltages and write back encoder state each tick. Subsystem PID controllers run against realistic simulated motor behavior, not instant state changes.
Vision cameras: Three simulated Limelights:
- limelight-two (LL4, AprilTag): 60 FPS, front-right mount — see
RebuiltSimManager.javafor mount angles - limelight-five (LL3, AprilTag): 30 FPS, front-left mount — see
RebuiltSimManager.javafor mount angles - limelight-one (LL3, Game Piece): 5 FPS, rear-facing mount — see
RebuiltSimManager.javafor mount angles and frustum distances
Field: 16.54m × 8.07m with two hubs, ramps, and fuel balls in neutral zones and depots.
Telemetry changes vs. earlier versions:
Robot/Intake/Extended(boolean) → replaced byRobot/Intake/ExtensionPct(0–100% double)Robot/Shooter/FeederOn,Robot/Shooter/SpindexerOn,Robot/Shooter/IsShootingremoved (were state-enum booleans, misleading with pulsed states)
Debug telemetry: 16 entries under Sim/Debug/ are published each tick for tuning and troubleshooting: ShooterVelocityRPS, ShooterVoltageIn, FeederVelocityRPS, FeederVoltageIn, SpindexerVelocityRPS, SpindexerVoltageIn, HoodAngleDeg, HoodVoltageIn, HoodPositionRot, IntakeDeployPositionRot, IntakeDeployExtendedPct, IntakeRollerVelocityRPS, IntakeZoneActive, ShootingGateOpen, BatteryVoltage, FuelHeld.
Shot cooldown: The shooter fires at a fixed rate. See SHOTS_PER_SECOND in RebuiltSimManager.java for the current value. The cooldown is 1.0 / SHOTS_PER_SECOND seconds between shot events.
Field mesh loading: RebuiltField tries the deploy directory first, falls back to classpath. Check console for warnings if the mesh isn’t found.
The Sim Loop (every 20ms)
- MapleSim steps drivetrain (motor voltages → tire forces → chassis state)
- Read robot pose + velocity from MapleSim
- Convert robot-relative speeds to world-frame velocities for ODE4J
- Update ODE4J chassis body (corrective velocity to track MapleSim pose)
- Wake nearby game pieces (proximity chunk activation)
- Check intake zone (before physics step, to prevent re-consuming launched balls) 6b. Enable/disable game piece detection sensors (FPS gating)
- ODE4J physics step (with adaptive sub-stepping)
- Sync gyro (MapleSim yaw → Pigeon2 sim state) 8b. Update AprilTag vision (write true pose to simulated Limelight NT entries) 8c. Update game piece detection cameras (read sensor contacts → publish tv/tx/ty/ta)
- Update game piece states (auto-disable settled pieces)
- Check scoring zones (sensor geom overlaps)
- Step all 6 mechanism physics sims and write back to CTRE sim states (shooter, hood, feeder, spindexer, intake deploy, intake roller)
- Update shooter (launch if firing + cooldown expired + hopper > 0)
- Publish telemetry (poses, scores, components, debug → AdvantageKit)
Design Patterns
Supplier-Based Decoupling
ShooterSim, IntakeZone, and other bridges use Supplier<T> / DoubleSupplier / BooleanSupplier to lazily read subsystem state each tick. This avoids snapshot inconsistencies within a tick and decouples sim-core from concrete subsystem classes. For example, ShooterSim receives a DoubleSupplier for hood angle (backed by SingleJointedArmSim.getAngleRads()) and a BooleanSupplier for the shooting gate (velocity-based checks on flywheel and feeder).
BiConsumer Publish Callback
GamePieceManager uses BiConsumer<String, Pose3d[]> for telemetry publishing. This decouples sim-core from AdvantageKit — the year-specific code provides the publish callback.
Kinematic Follower
MapleSim owns the “truth” for robot pose. ODE4J applies corrective forces (F = mass × (v_desired - v_current) / dt) to match, while ODE4J’s contact constraints naturally prevent wall penetration. This gives you the best of both engines without double-counting.
Building a Sim for a New Game Year
- Define game piece properties — shape, mass, radius, bounce via
GamePieceConfig.Builder - Generate the field collision mesh — see below
- Configure the chassis — mass, dimensions via
ChassisConfig.Builder - Write the SimManager — initialize MapleSim + sim-core, run the sim loop, publish telemetry
- Add scoring zones — sensor geoms at scoring locations, register with
ScoringTracker - Add mechanism bridges — wire each non-drivetrain motor to a WPILib physics sim (
DCMotorSim,SingleJointedArmSim), then connect subsystem state to intake zones and launch parameters via suppliers
Use RebuiltSimManager as the reference implementation.
Generating the Field Collision Mesh
The sim needs an OBJ file that defines the field’s collision surfaces (walls, ramps, hubs, etc.). We use FEDS Bot to generate a Python script that outputs the OBJ from hardcoded field dimensions. See robot/2026-rebuilt/src/main/resources/generate_field.py for the 2026 example.
The workflow:
- Write a prompt asking for a Python script to generate this year’s field collision mesh. Include field details — both manually written descriptions and references from the game manual. See the 2026 prompt as an example.
- Give the prompt to FEDS Bot (make sure you’ve added the new game manual PDF to
./game-manuals/first so it has context). - Save the generated script to
robot/20XX-GAMENAME/src/main/resources/generate_field.py - Run it — it produces
field_collision.obj - Visually inspect the OBJ at 3dviewer.net , then load it in the sim and drive around in AdvantageScope — verify that obstacles line up with the visual field
- If something’s off, go back to FEDS Bot to tweak the script and repeat from step 3
Keep field OBJ meshes simple. Every triangle is a collision surface. 500 triangles is fine. 50,000 will destroy your frame rate.
Troubleshooting
Robot doesn’t move: Check that the sim GUI shows “Enabled” in “Teleop”. Make sure a controller or keyboard is connected.
Balls fall through the floor: Verify PhysicsWorld has gravity enabled and the OBJ mesh loaded without errors.
Balls tunnel through walls: Adaptive sub-stepping should prevent this. If it happens, the launch velocity may exceed the 0.1m sub-step threshold. Also check the known chunk-boundary bug noted in the Proximity Sleep/Wake section above.
ClassNotFoundException: frc.sim.core.PhysicsWorld: sim-core isn’t on the classpath. In settings.gradle:
include ':sim-core'
project(':sim-core').projectDir = new File(settingsDir, '../sim-core')And in build.gradle:
implementation project(':sim-core')Slow performance: Check active piece count. The proximity system should keep active pieces well under 100. Also make sure you ran the mesh simplify script.
Encoder mismatch: Check MapleSim gear ratios match the physical robot config.