AbsoluteLib is an FRC utility library for Team 4308. It provides reusable subsystems + wrappers with a focus on "same code in real + sim".
- Vendor install:
https://team4308.github.io/absolutelib/lib/absolutelib.json - Docs site:
https://team4308.github.io/absolutelib/ - JavaDoc site:
https://team4308.github.io/absolutelib/docs/javadoc
- WPILib VS Code →
Ctrl+Shift+P WPILib: Manage Vendor LibrariesInstall new library (online)- Paste:
https://team4308.github.io/absolutelib/lib/absolutelib.json
Before building, install all required libraries:
- Rev Hardware Client
- AdvantageKit
- PathPlannerLib
- Phoenix6-Replay (6 and 5)
- PhotonLib
- REVLib
- Studica
- ThriftyLib
- YAGSL
Note: Your build WILL fail if you don't add these vendordeps.
MotorWrapper: TalonFX (Phoenix6), TalonSRX/VictorSPX (Phoenix5), SparkMax (REV) unified APIEncoderWrapper: Unified encoder access (CANCoder, SparkMax encoder, etc.)
Arm: Multi-joint arm with IK support (2+ DOF arms with inverse kinematics)Pivot: Single-joint rotational control (PID + FF, optional Smart Motion)Elevator: Linear elevator control (PID + FF, optional Smart Motion)EndEffector: Base class for intakes, claws, and manipulators
ArmSimulation: Physics sim for multi-DOF armsPivotSimulation: Physics sim viaSingleJointedArmSimElevatorSimulation: Physics sim viaElevatorSim
Vision: PhotonVision wrapper + multi-camera support for pose estimationleds/*: Addressable LED patterns and simulation helpers
ChineseRemainderSolver: Generic CRT solver + turret anti-windup (shortest-path rotation within cable limits)DoubleUtils: Clamping, normalization, range mappingVector2/Vector3: Lightweight vector math
TrajectorySolver: Complete trajectory solving for turret shooters with obstacle avoidanceShooterSystem: Integrated state machine for managing shots, tracking, and fallback strategiesFlywheelGenerator: Automated flywheel configuration generation and optimizationFlywheelSimulator: Physics-based flywheel and ball exit velocity simulationProjectileMotion: Projectile physics with air resistance, drag, and Magnus effectObstacleConfig: Collision-aware field obstacle definition (e.g., 2026 hub)SolverConstants: Runtime-tunable constants for all solver behaviorGamePieces: Predefined game pieces including 2026 REBUILT ball
Under ./example/example-2026-Imported you can find full robot code for all subsystems + simulation.
AbsoluteLib simulations follow this pattern:
- Subsystem computes output (PID + FF) → produces a voltage or percent output
- Subsystem applies output to motor (real hardware OR sim state)
- In SIM: subsystem passes the same computed voltage into the simulation object
- Simulation updates position/velocity and writes them back into:
- Encoder sim position
- Motor controller sim state (when supported)
import ca.team4308.absolutelib.wrapper.MotorWrapper;
import ca.team4308.absolutelib.wrapper.MotorWrapper.MotorType;
public class ShooterIO {
// Control TalonFX, SparkMax, or TalonSRX with the same API
private final MotorWrapper leader = new MotorWrapper(MotorType.TALONFX, 10);
private final MotorWrapper feeder = new MotorWrapper(MotorType.SPARKMAX, 11);
public void runVolts(double volts) {
leader.setVoltage(volts);
}
public void stop() {
leader.stop();
feeder.stop();
}
}Single-joint rotational subsystem with PID control and simulation.
import ca.team4308.absolutelib.subsystems.Pivot;
import ca.team4308.absolutelib.subsystems.simulation.PivotSimulation;
import ca.team4308.absolutelib.wrapper.MotorWrapper;
import ca.team4308.absolutelib.wrapper.EncoderWrapper;
import edu.wpi.first.math.system.plant.DCMotor;
public class Wrist extends Pivot {
public Wrist() {
super(new Pivot.Config()
.withLeader(new MotorWrapper(MotorWrapper.MotorType.TALONFX, 15))
.withEncoder(EncoderWrapper.canCoder(20, 1.0)) // 1.0 = ratio derived from gearbox
.gear(50.0)
.limits(-90, 90)
.pid(0.02, 0.0, 0.0)
.ff(0.0, 0.15, 0.0, 0.0)
.enableSimulation(true)
.withSimulation(new PivotSimulation.Config()
.gearbox(DCMotor.getFalcon500(1), 1)
.gearRatio(50.0)
.armLength(0.30)
.armMass(2.0)
.limits(Math.toRadians(-90), Math.toRadians(90))
.startAngle(0.0)
)
);
}
public Command goToStow() { return setPosition(0.0); }
public Command goToScore() { return setPosition(45.0); }
}Multi-DOF arm with inverse kinematics for Cartesian (x,y) positioning.
import ca.team4308.absolutelib.subsystems.Arm;
import ca.team4308.absolutelib.wrapper.MotorWrapper;
import ca.team4308.absolutelib.wrapper.EncoderWrapper;
public class ExampleArm {
private final Arm arm = new Arm();
private final Arm.Joint shoulder;
public ExampleArm() {
// Shoulder setup
MotorWrapper shoulderMotor = new MotorWrapper(MotorType.TALONFX, 30);
EncoderWrapper shoulderEncoder = EncoderWrapper.ofMechanismRotations(
shoulderMotor::getPosition,
val -> shoulderMotor.asTalonFX().setPosition(val),
1.0 / Math.PI // Conversion factor
);
Arm.JointConfig shoulderConfig = Arm.JointConfig.builder()
.minAngleRad(-Math.PI / 2)
.maxAngleRad(Math.PI / 2)
.metersToRadians(2 * Math.PI)
.linkLengthMeters(1.0)
.build();
shoulder = arm.addJoint(shoulderMotor, null, shoulderEncoder, shoulderConfig);
shoulder.setPositionPID(32, 0, 0);
shoulder.setFeedforwardGains(0.1, 0.1, 0.1, 0.1);
// ... Add Elbow joint similarly ...
arm.enableSimulation(true);
arm.initialize();
}
// Modern IK control: Move end-effector to (x,y)
public Command moveToPoint(double x, double y) {
return runOnce(() -> arm.setGoalPose(x, y));
}
}Seamless simulation-compatible vision integration.
import ca.team4308.absolutelib.vision.Vision;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
public class VisionSubsystem {
private final Vision vision;
public VisionSubsystem(SwerveDrive drive) {
AprilTagFieldLayout layout = AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark);
var frontCam = new Vision.VisionCamera(
"FrontCam",
layout,
new Rotation3d(0, 0, 0),
new Translation3d(0.30, 0.0, 0.20), // Camera offset from center
VecBuilder.fill(0.8, 0.8, 2.0), // Single tag trust
VecBuilder.fill(0.3, 0.3, 1.0) // Multi-tag trust
);
vision = new Vision(drive::getPose, drive.field, layout, frontCam);
}
// Call in periodic to update odometry
public void updatePose(SwerveDrive drive) {
vision.updatePoseEstimation(drive);
vision.updateVisionField(); // Updates SmartDashboard field
}
}The layout for 2026 includes a powerful ShooterSystem state machine that integrates the TrajectorySolver with lookup tables and real-time physics.
import ca.team4308.absolutelib.math.trajectories.*;
import ca.team4308.absolutelib.math.trajectories.shooter.*;
public class Shooter {
private final ShooterSystem shooterSystem;
private final TrajectorySolver solver;
public Shooter() {
// 1. Configure Solver
TrajectorySolver.SolverConfig solverConfig = TrajectorySolver.SolverConfig.defaults()
.toBuilder()
.minPitchDegrees(47.5)
.maxPitchDegrees(82.5)
.build();
solver = new TrajectorySolver(GamePieces.REBUILT_2026_BALL, solverConfig);
// SWEEP mode finds best angle by testing candidates (thorough)
// ITERATIVE mode is faster but less robust for complex obstacles
solver.setSolveMode(TrajectorySolver.SolveMode.SWEEP);
// 2. Configure Shooter Limits
ShooterConfig config = ShooterConfig.builder()
.pitchLimits(47.5, 82.5)
.rpmLimits(0, 6000)
.distanceLimits(0.5, 12.0)
.safetyMaxExitVelocity(30.0)
.build();
// 3. Define Lookup Table (Fallback)
ShotLookupTable table = new ShotLookupTable()
.addEntry(1.0, 78.0, 1000)
.addEntry(2.0, 72.0, 1300)
.addEntry(4.0, 59.0, 2100)
.addEntry(6.0, 52.0, 2700);
// 4. Initialize System
shooterSystem = new ShooterSystem(config, table, solver);
shooterSystem.setMode(ShotMode.SOLVER_WITH_LOOKUP_FALLBACK);
}
public void periodic() {
// Calculate shot based on current robot state
ShotParameters shot = shooterSystem.calculate(
distanceMeters,
currentFlywheelRpm,
robotVx, robotVy,
robotYawRadians
);
if (shot.valid) {
// Apply shot.pitchDegrees and shot.rpm
}
}
}The 2026 solver can be configured to avoid field structures (like the Hub).
// Define Obstacle
ObstacleConfig hub = ObstacleConfig.builder()
.position(4.03, 4.0)
.baseSize(1.19)
.wallHeight(1.83)
.build();
// Add to Shot Input
ShotInput input = ShotInput.builder()
.shooterPositionMeters(x, y, z)
.targetPositionMeters(tx, ty, tz)
.addObstacle(hub)
.collisionCheckEnabled(true)
.build();All physics constants are runtime-tunable via SolverConstants:
SolverConstants.setVelocityBufferMultiplier(1.2); // 20% extra velocity buffer
SolverConstants.setDragCompensationMultiplier(1.0); // Air resistance factorEnable debug logging to see exactly why shots are chosen or rejected:
solver.setDebugEnabled(true);
// Logs accepted/rejected candidates, physics calculations, and flight pathsWhen a new version of AbsoluteLib is released, follow these steps to update:
- WPILib VS Code →
Ctrl+Shift+P WPILib: Manage Vendor LibrariesCheck for updates (online)- If AbsoluteLib shows an update, accept it.
This works because the vendor JSON URL points to the latest published version.
- WPILib VS Code →
Ctrl+Shift+P WPILib: Manage Vendor LibrariesInstall new library (online)- Paste:
https://team4308.github.io/absolutelib/lib/absolutelib.json - If prompted to replace the existing version, confirm.
- Rebuild your project (
Ctrl+Shift+P→WPILib: Build Robot Code).
- Open
vendordeps/absolutelib.jsonin your robot project. - Update the
"version"fields to the new version number. - Update the
javaDependencies[0].versionto match. - Rebuild.
Tip: After updating, always do a clean build (
./gradlew clean build) to avoid stale cached artifacts.
To publish a new release of AbsoluteLib:
scripts\release.batThis single script handles the entire release process:
- Safety checks — verifies you're on
master, inside the repo, and required files exist - Version bump — prompts for a new version and auto-updates
gradle.propertiesandabsolutelib.json - Backup — creates a timestamped local backup in
.git-backup-cache/ - Commit & push master — stages, commits, and pushes to the
masterbranch - Gradle build — runs
publishPagesRepoto generate Maven artifacts and Javadoc - Site staging — assembles the full GitHub Pages site (docs + Maven repo + Javadoc + vendor JSON)
- Deploy gh-pages — force-pushes the built site to the
gh-pagesbranch
No other scripts need to be run — release.bat replaces the old publish.bat and build-pages-site.bat scripts.
- WPILib — Go into the
build.gradlefile and changewpilibVersionto the year. You may also have to updateWPILibRepositoriesPluginonly if they rework vendors. - Libraries — Also in the
build.gradlefile, scroll down to thedependenciesblock and update each package as needed.