FIRST Tech Challenge · #30410 · Pasadena, CA

Axiomatic Moonwalkers

Axiomatic

Moonwalkers

Lorem ipsum dolor sit amet, consectetur adipiscing elit.

We build competition robots out of a home design lab in Pasadena. The garage is our machine shop, the living room is a full-size field, and we share what we build along the way.

Our DECODE competition robot

DECODE Bot · 2025–26 season

Our home design lab
Our pit at a competition
Explaining the build to judges
The turret up close

Who we are

Built at home, shared with everyone

With no school shop, we turned home into a design lab. The garage became a machine shop and the living room a full-size FTC field. Most of our parts came secondhand from a team that was shutting down, which kept the whole thing on a student budget.

We're a small team and growing. We open-source our code and post the whole build on YouTube, the wins and the parts that break, so other teams can learn from what we figure out.

  • Control Award
  • 20k+ reached
  • Open source

What we do

Built from first principles

One team, every discipline, designed, built, coded, and shared in the open.

CAD render of the Axiomatic robot
3D model

01 · Design

Design

Every subsystem starts in CAD. The hooded shooter, turret, and intake are modeled in Fusion 360 and refined across versions before a single part is cut. (Interactive 3D coming soon.)

Build log

02 · Build

Build

Fabricated and iterated in a home design lab, printed parts swapped for metal, the shooter rewired, and the drivetrain hardened to survive competition. (Hover to flip through the build.)

NewDecodeBot.javaRFrame
package com.buddyram.rframe.ftc.v3;

import com.buddyram.rframe.Logger;
import com.buddyram.rframe.Odometry;
import com.buddyram.rframe.Pose3D;
import com.buddyram.rframe.RobotException;
import com.buddyram.rframe.Vector3D;
import com.buddyram.rframe.actions.RobotAction;
import com.buddyram.rframe.actions.TimeoutWrapperAction;
import com.buddyram.rframe.drive.HolonomicDriveInstruction;
import com.buddyram.rframe.drive.HolonomicDriveTrain;
import com.buddyram.rframe.drive.Navigatable;
import com.buddyram.rframe.ftc.DriveToAction;
import com.buddyram.rframe.ftc.v3.Robot.intake.Intake;
import com.buddyram.rframe.ftc.v3.Robot.launcher.Launcher;

public class NewDecodeBot implements Navigatable<HolonomicDriveTrain> {
    public enum AutoStep { NEAR, MIDDLE, FAR, OPEN_GATE_LEFT, OPEN_GATE_BLOCK_AFTER_NEAR, SHOOT, INTAKE_GATE }

    public static class AutoSequenceConfig {
        public final Vector3D shootPos;
        public final Vector3D firstShotPos;
        public final double shootHeading;
        public final AutoStep[] steps;
        public final Vector3D parkPos;
        public final int firstTurretWaitMs;
        public final int turretWaitMs;

        public AutoSequenceConfig(Vector3D firstShotPos, Vector3D shootPos, double shootHeading,
                                  AutoStep[] steps, Vector3D parkPos,
                                  int firstTurretWaitMs, int turretWaitMs) {
            this.firstShotPos = firstShotPos;
            this.shootPos = shootPos;
            this.shootHeading = shootHeading;
            this.steps = steps;
            this.parkPos = parkPos;
            this.firstTurretWaitMs = firstTurretWaitMs;
            this.turretWaitMs = turretWaitMs;
        }

        public AutoSequenceConfig(Vector3D firstShotPos, Vector3D shootPos, double shootHeading,
                                  AutoStep[] steps, Vector3D parkPos) {
            this(firstShotPos, shootPos, shootHeading, steps, parkPos, 1000, 1000);
        }
    }
    public boolean block = true;
    public Logger logger;
    public Odometry<Pose3D> odometry;
    private static final Vector3D BLUE_GOAL = new Vector3D(0, 144, 0);
    private static final Vector3D RED_GOAL = new Vector3D(144, 144, 0);
    public boolean isRed;
    public double turretOffset = 0;
    public boolean jamFix = false;

    public Odometry<Pose3D> getApriltagOdometry() {
        return apriltagOdometry;
    }

    public Odometry<Pose3D> apriltagOdometry;
    public HolonomicDriveTrain drive;

    public Intake getIntake() {
        return intake;
    }

    public Intake intake;

    public boolean aimOn = false;

    public Launcher getLauncher() {
        return launcher;
    }

    public Launcher launcher;

    public Vector3D targetGoal;

    public NewDecodeBot() {
        this(null, null, null, null, null, null, false);
    }
    public NewDecodeBot(Logger logger, Odometry<Pose3D> odometry, HolonomicDriveTrain drive, Launcher launcher, Intake intake, Odometry<Pose3D> apriltagOdometry, boolean isRed) {
        this.init(logger, odometry, drive, launcher, intake, apriltagOdometry, isRed);
    }

    public void init(Logger logger, Odometry<Pose3D> odometry, HolonomicDriveTrain drive, Launcher launcher, Intake intake, Odometry<Pose3D> apriltagOdometry, boolean isRed) {
        this.logger = logger;
        this.odometry = odometry;
        this.drive = drive;
        this.launcher = launcher;
        this.intake = intake;
        this.apriltagOdometry = apriltagOdometry;
        this.isRed = isRed;
        this.targetGoal = isRed ? RED_GOAL : BLUE_GOAL;
    }

    @Override
    public Odometry<Pose3D> getOdometry() {
        return this.odometry;
    }

    @Override
    public HolonomicDriveTrain getDrive() {
        return this.drive;
    }

    @Override
    public Logger getLogger() {
        return this.logger;
    }

    @Override
    public boolean isActive() {
        return true;
    }

    public HolonomicDriveInstruction calculateRelativeDriveInstruction(Vector3D relativeTarget, double speed) {
        return this.calculateDriveInstruction(relativeTarget.add(this.odometry.get().position), speed);
    }
    public class AdjustFlywheelSpeedAction implements RobotAction<NewDecodeBot>  {
        @Override
        public boolean run(NewDecodeBot drive) throws RobotException {
            drive.adjustFlywheelSpeed();
            return true;
        }
    }
    public int speed = 0;
    public Double overrideHood = null;
    public Double overrideDistance = null;
    public double hoodOffset = 0;
    public void adjustFlywheelSpeed() {
        if (this.launcher == null) return;
        double dist = overrideDistance == null ? this.odometry.get().position.distance(this.targetGoal) : overrideDistance;
        this.getLauncher().wheel.setRPM(Math.max(2350.50621 * Math.pow(1.00529, dist) + speed, 0));
        this.launcher.hood.setAngle(calculateHoodAngle(dist) + hoodOffset);
        if (overrideHood != null) {
            this.launcher.hood.setAngle(overrideHood);
        }
    }

    public double calculateHoodAngle(double dist) {
        return -0.000000109377 * Math.pow(dist, 3) + 0.0000691154 * Math.pow(dist, 2) - 0.0111601 * dist + 1.02966;
    }
    public Double overrideAngle = null;

    /**
     * Calculates the turret angle needed to hit the goal from a given position and heading.
     * Use this to preload the turret during a drive so it's ready to shoot on arrival.
     */
    public double calculateTurretAngle(Vector3D fromPosition, double heading) {
        Vector3D posToGoal = this.targetGoal.sub(fromPosition);
        double angle = (Math.toDegrees(Math.atan2(posToGoal.y, posToGoal.x)) - 90 - heading + turretOffset) % 360;
        if (angle < 0) angle += 360;
        angle = angle > 180 ? angle - 360 : angle;
        return angle;
    }

    /**
     * Preloads the turret angle for a future shooting position/heading.
     * Sets overrideAngle so the turret starts moving immediately, even while driving.
     */
    public void preloadTurretForPosition(Vector3D shootPosition, double shootHeading) {
        this.aimOn = true;
        this.overrideAngle = calculateTurretAngle(shootPosition, shootHeading);
    }

    /**
     * Waits until the turret motor reaches its target position, with a timeout.
     */
    public void waitForTurret(int timeoutMs) throws RobotException {
        long start = System.currentTimeMillis();
        while (!this.launcher.turret.isReady()) {
            if (System.currentTimeMillis() - start > timeoutMs) {
                System.out.println("[AUTO] waitForTurret timed out after " + timeoutMs + "ms");
                break;
            }
            try { Thread.sleep(10); } catch (InterruptedException e) { throw new RuntimeException(e); }
        }
    }

    /**
     * Waits until the turret's actual angle is within the threshold of the
     * live-calculated target angle (based on current robot position).
     */
    public void waitUntilAimed(double thresholdDegrees, int timeoutMs) {
        long start = System.currentTimeMillis();
        while (System.currentTimeMillis() - start < timeoutMs) {
            Pose3D pos = this.odometry.get();
            double targetAngle = calculateTurretAngle(pos.position, pos.rotation.z);
            double currentAngle = this.launcher.turret.getCurrentAngle();
            double diff = targetAngle - currentAngle;
            if (diff > 180) diff -= 360;
            if (diff < -180) diff += 360;
            if (Math.abs(diff) <= thresholdDegrees) {
                return;
            }
            try { Thread.sleep(10); } catch (InterruptedException e) { throw new RuntimeException(e); }
        }
        System.out.println("[AUTO] waitUntilAimed timed out after " + timeoutMs + "ms");
    }

    public double autoAim() {
        if (this.launcher == null) return 0;
        Vector3D posToGoal = this.targetGoal.sub(this.odometry.get().position);
        double angle = (Math.toDegrees(Math.atan2(posToGoal.y, posToGoal.x)) - 90 - this.odometry.get().rotation.z + turretOffset) % 360;
        if (angle < 0) angle += 360;
        angle = angle > 180 ? angle - 360 : angle;
        if (overrideAngle != null) {
            angle = overrideAngle;
        }
        if (!aimOn) {
            angle = 0;
        }
        this.launcher.turret.setAngle(angle);
        return angle;
    }

    public HolonomicDriveInstruction calculateDriveInstruction(Vector3D target, double speed) {
        double rotationInstruction = 0, driveSpeedInstruction = 0, driveAngleInstruction = 0;
        Pose3D pos = this.odometry.get();
        driveSpeedInstruction = speed;
        driveAngleInstruction = pos.position.calculateRotation(target).z;

        return new HolonomicDriveInstruction(rotationInstruction, driveSpeedInstruction, driveAngleInstruction);
    }

    public void controlIntake() {
        if (this.launcher == null || this.intake == null) return;
        this.launcher.blocker.setAngle(this.block ? this.launcher.blocker.OPEN : this.launcher.blocker.CLOSED);
        if (jamFix) {
            this.intake.enableMode(Intake.Modes.INTAKING);
            return;
        }
        else {
            this.intake.enableMode(Intake.Modes.IDLE);
        }
    }

    private void logPos(String label) {
        Pose3D pos = this.odometry.get();
        System.out.println("[AUTO] " + label + " pos=(" +
            String.format("%.2f", pos.position.x) + ", " +
            String.format("%.2f", pos.position.y) + ") heading=" +
            String.format("%.2f", pos.rotation.z));
    }

    public void intakeFromGate() throws RobotException {
        BotUtilsNew.driveAndRotateTo(new Vector3D(114, 60, 0), -90).run(this);
        BotUtilsNew.driveAndRotateTo(new Vector3D(128, 57.92, 0), -60.49).run(this);
        double time = System.currentTimeMillis();
        jamFix = true;
        BotUtilsNew.driveTowardsUntil(131, 58.56, (pos) -> System.currentTimeMillis() - time > 1100 , 0.3).run(this);
        jamFix = false;
    }
    public void intakeWhileBlocking() throws RobotException {
        BotUtilsNew.driveAndRotateTo(new Vector3D(126.7, 64.54, 0), 14.35).run(this);
        double time = System.currentTimeMillis();
        BotUtilsNew.driveTowardsUntil(128.68, 64.5, (pos) -> System.currentTimeMillis() - time > 300, 0.8).run(this);
        BotUtilsNew.driveAndRotateTo(new Vector3D(130, 58, 0), 15.92).run(this);
    }

    public void intakeTick(double x, double y) throws RobotException {
        jamFix = true;
        BotUtilsNew.driveAndRotateTo(BotUtilsNew.mirrorIfRed(new Vector3D(45, y, 0), isRed), BotUtilsNew.mirrorIfRed(90, isRed)).run(this);
        logPos("intakeTick approach (45," + y + ")@110");
        new TimeoutWrapperAction<>(BotUtilsNew.driveTo(BotUtilsNew.mirrorIfRed(new Vector3D(x, y, 0), isRed), false), 1600).run(this);
        logPos("intakeTick pickup (" + x + "," + y + ")@90");
    }

    public void intakeTickFar() throws RobotException {
        intakeTick(18, 36);
    }
    public void intakeTickMiddle() throws RobotException {
        intakeTick(15, 56);
    }

    public void intakeTickClose() throws RobotException {
        new TimeoutWrapperAction<>(BotUtilsNew.driveAndRotateTo(BotUtilsNew.mirrorIfRed(new Vector3D(19, 84, 0), isRed), BotUtilsNew.mirrorIfRed(90, isRed)), 1600).run(this);
        logPos("intakeTickClose (12,84)@90");
    }

    public void runStep(AutoStep step) throws RobotException {
        switch (step) {
            case NEAR: intakeTickClose(); break;
            case MIDDLE: intakeTickMiddle(); break;
            case FAR: intakeTickFar(); break;
            case OPEN_GATE_LEFT: openGateLeft(); break;
            case OPEN_GATE_BLOCK_AFTER_NEAR: intakeWhileBlocking();
            case INTAKE_GATE: intakeFromGate();
        }
    }

    private static final Vector3D SHOOT_POSITION = new Vector3D(50, 84, 0);
    private static final int SHOOT_HEADING = 90;
    public void shootImmediate(Vector3D shootPos, double shootHeading, int turretWaitMs) throws RobotException {
        // Preload turret toward estimated shoot position so it's moving while we drive
        preloadTurretForPosition(BotUtilsNew.mirrorIfRed(shootPos, isRed), BotUtilsNew.mirrorIfRed(shootHeading, isRed));

        // Drive toward shoot position. Stops as soon as it enters a shooting zone.
        Vector3D driveTarget = BotUtilsNew.mirrorIfRed(shootPos, isRed);
        BotUtilsNew.driveTowardsUntil(driveTarget.x, driveTarget.y, (pos) -> DecodeGameMap.isInShootingZone(pos.position.x, pos.position.y, pos.rotation.z), 0.9).run(this);
        this.getDrive().drive(new HolonomicDriveInstruction(0, 0, 0));
        logPos("shootImmediate entered shooting zone");

        // Use actual distance for hood/RPM so we don't overshoot at close range
        this.overrideDistance = this.odometry.get().position.distance(this.targetGoal);

        // Switch to live auto-aim and wait until turret is within 3 degrees of real target
        overrideAngle = null;
        waitUntilAimed(3, turretWaitMs);

        // Shoot
        this.jamFix = true;
        this.block = false;
        BotUtilsNew.wait(1300).run(this);
        this.block = true;
    }

    public void shootFrom(Vector3D shootPos, double shootHeading, int turretWaitMs) throws RobotException {
        // Turret should already be preloaded from prior step; drive to shooting position
        this.aimOn = true;
        BotUtilsNew.driveAndRotateTo(BotUtilsNew.mirrorIfRed(shootPos, isRed), BotUtilsNew.mirrorIfRed(shootHeading, isRed), 8).run(this);
        logPos("shootFrom arrived (" + shootPos.x + "," + shootPos.y + ")@" + shootHeading);

        // Switch to live auto-aim and wait for turret/flywheel to settle
        overrideAngle = null;
        waitForTurret(turretWaitMs);

        // Shoot
        this.jamFix = true;
        this.block = false;
        BotUtilsNew.wait(1300).run(this);
        this.block = true;
    }

    public void shootClose() throws RobotException {
        shootFrom(SHOOT_POSITION, SHOOT_HEADING, 1000);
    }

    public void openGateLeft() throws RobotException {
        // Fast approach - just get close to alignment position
        new DriveToAction<NewDecodeBot>(BotUtilsNew.mirrorIfRed(new Vector3D(30, 72, 0), isRed), 8, (dist) -> 0.8, false).run(this);
        logPos("openGateLeft approach");
        // Push with heading alignment, timeout prevents stalling
        jamFix = false;
        new TimeoutWrapperAction<>(BotUtilsNew.driveAndRotateTo(BotUtilsNew.mirrorIfRed(new Vector3D(9, 72, 0), isRed), BotUtilsNew.mirrorIfRed(90, isRed)), 500).run(this);
        logPos("openGateLeft push");
        BotUtilsNew.wait(800).run(this);
        jamFix = true;
        // Fast back away
        new DriveToAction<NewDecodeBot>(BotUtilsNew.mirrorIfRed(new Vector3D(40, 60, 0), isRed), 8, (dist) -> 0.8, false).run(this);
    }

    public void updateGlobals() {
        Globals.POSITION = this.odometry.get();
    }

    public void runAutoSequence(AutoSequenceConfig config) throws RobotException {
        logPos("AUTO START");

        if (this.launcher != null) {
            this.overrideDistance = BotUtilsNew.mirrorIfRed(config.shootPos, isRed).distance(targetGoal);
            // Preload turret toward first shot position so it's already aimed when we arrive
            preloadTurretForPosition(BotUtilsNew.mirrorIfRed(config.firstShotPos, isRed), BotUtilsNew.mirrorIfRed(config.shootHeading, isRed));
        }

        boolean firstShot = true;
        for (AutoStep step : config.steps) {
            logPos("before " + step);
            if (step == AutoStep.SHOOT) {
                if (this.launcher == null) {
                    logPos("skipping SHOOT (no launcher)");
                    continue;
                }
                if (firstShot) {
                    shootFrom(config.firstShotPos, config.shootHeading,
                            config.firstTurretWaitMs);
                } else {
                    shootImmediate(config.shootPos, config.shootHeading, config.turretWaitMs);
                }
                firstShot = false;
            } else if (step == AutoStep.INTAKE_GATE || step == AutoStep.OPEN_GATE_BLOCK_AFTER_NEAR) {
                if (this.intake == null) {
                    logPos("skipping " + step + " (no intake)");
                    continue;
                }
                runStep(step);
            } else {
                runStep(step);
            }
            logPos("after " + step);
        }

        // Park
        BotUtilsNew.driveAndRotateTo(BotUtilsNew.mirrorIfRed(config.parkPos, isRed), 0).run(this);
        logPos("after final park");
        this.jamFix = false;
        this.aimOn = false;
    }
}
View robot code

03 · Code

Code

RFrame, a custom framework powering odometry, autonomous actions, and subsystems. A scratch-built pathing system scores 10–12 artifacts in autonomous.

Axiomatic giving a robotics demo at Blue Ridge Academy
Outreach

04 · Share

Share

The @axiomatic-robotics channel has reached 20,000+ people across 50 countries, plus live demos, active FTC Discord help, and hands-on mentoring for other teams.