CrocoDocs
CrocoDocs

Introduction

What is CrocoDocs?Season Breakdown

Getting Started

Programming in FTCJavaBlocksAndroid Studio

Control Systems

IntroductionJoystick MappingPID ControlMotion ProfilingKalman FilterLow-Pass Filter

Autonomous

IntroductionTime vs Encoder-Based MovementOdometryMotion PlanningPure PursuitSensor Fusion

Codebase Etiquette and Good Practices

IntroductionNaming ConventionsCode OrganizationComments and DocumentationTeam Collaboration

Libraries

LibrariesNextFTCPedro PathingFTC DashboardMercurialPanelsSloth

Sensors and Vision

Vision OverviewVision Basics

NextFTC

Command-based framework with built-in control systems and gamepad bindings

What is NextFTC?

NextFTC is a collection of powerful libraries designed to make FTC programming easier and more organized. It includes:

  • NextFTC Core - Command-based framework with commands, subsystems, and components
  • NextControl - Advanced control systems (PID, feedforward, Bang-Bang)
  • NextBindings - Gamepad integration with button bindings and edge detection
  • Hardware Module - Built-in commands for motors, servos, and drivetrains
  • Extensions - Integration with Pedro Pathing and Road Runner

Think of it like having a professional toolkit instead of starting from scratch every time.

Why Use NextFTC?

Command-Based Programming:

  • Organize code into reusable commands
  • Prevent conflicts with subsystem requirements
  • Run commands sequentially or in parallel
  • Build complex autonomous routines easily

Advanced Control:

  • Built-in PID, feedforward, and Bang-Bang controllers
  • Clean API for control systems
  • Everything integrates seamlessly

Better Gamepad Handling:

  • Bind callbacks to button presses
  • Rising and falling edge detection
  • Automatic gamepad polling
  • Joystick curving and dead zones

Key Benefits:

  • ✅ Less boilerplate code than vanilla FTC
  • ✅ Professional command-based architecture
  • ✅ Built-in hardware commands for common tasks
  • ✅ Excellent control systems included
  • ✅ Active development and support
  • ✅ Extensions for popular pathing libraries

Installation

NextFTC Core + Hardware Module

In your build.gradle (Module: TeamCode), add:

dependencies {
    implementation 'dev.nextftc:ftc:1.0.1'
    implementation 'dev.nextftc:hardware:1.0.1'  // Optional hardware module
}

NextControl (Optional)

implementation 'dev.nextftc:control:1.0.0'

NextBindings (Optional)

implementation 'dev.nextftc:bindings:1.0.1'

Then click "Sync Now" in Android Studio.

Note: Check nextftc.dev for the latest versions.

Core Concepts

Commands

Commands have four main components: start, update, stop, and isDone.

// Lambda command - the main way to create commands
LambdaCommand myCommand = new LambdaCommand()
    .setStart(() -> {
        // Runs once when command starts
        armMotor.setTargetPosition(1000);
    })
    .setUpdate(() -> {
        // Runs every loop
        armMotor.setPower(0.8);
    })
    .setStop((interrupted) -> {
        // Runs once when command ends
        armMotor.setPower(0);
    })
    .setIsDone(() -> {
        // Returns true when command is finished
        return Math.abs(armMotor.getCurrentPosition() - 1000) < 10;
    })
    .setInterruptible(true)  // Optional
    .named("Move Arm");       // Optional
// Lambda command - the main way to create commands
val myCommand = LambdaCommand()
    .setStart { 
        // Runs once when command starts
        armMotor.targetPosition = 1000
    }
    .setUpdate { 
        // Runs every loop
        armMotor.power = 0.8
    }
    .setStop { interrupted ->
        // Runs once when command ends
        armMotor.power = 0.0
    }
    .setIsDone { 
        // Returns true when command is finished
        Math.abs(armMotor.currentPosition - 1000) < 10
    }
    .setInterruptible(true)  // Optional
    .named("Move Arm")        // Optional

Commands as Classes (for reusability):

public class MoveArmCommand extends Command {
    private DcMotor motor;
    private int target;
    
    public MoveArmCommand(DcMotor motor, int target) {
        this.motor = motor;
        this.target = target;
    }
    
    @Override
    public void start() {
        motor.setTargetPosition(target);
    }
    
    @Override
    public void update() {
        motor.setPower(0.8);
    }
    
    @Override
    public void stop(boolean interrupted) {
        motor.setPower(0);
    }
    
    @Override
    public boolean isDone() {
        return Math.abs(motor.getCurrentPosition() - target) < 10;
    }
}
class MoveArmCommand(
    private val motor: DcMotor,
    private val target: Int
) : Command() {
    
    override fun start() {
        motor.targetPosition = target
    }
    
    override fun update() {
        motor.power = 0.8
    }
    
    override fun stop(interrupted: Boolean) {
        motor.power = 0.0
    }
    
    override val isDone: Boolean
        get() = Math.abs(motor.currentPosition - target) < 10
}

Scheduling Commands:

// Method 1: Use CommandManager
CommandManager.scheduleCommand(myCommand);

// Method 2: Commands are Runnable - just call them
myCommand();
// Method 1: Use CommandManager
CommandManager.scheduleCommand(myCommand)

// Method 2: Commands are Runnable - just call them
myCommand()

Subsystems

Subsystems organize your robot's mechanisms. Use singletons to ensure only one instance exists:

public class ArmSubsystem implements Subsystem {
    private static ArmSubsystem instance;
    private DcMotor armMotor;
    
    private ArmSubsystem() {
        // Private constructor
    }
    
    public static ArmSubsystem getInstance(HardwareMap hardwareMap) {
        if (instance == null) {
            instance = new ArmSubsystem();
            instance.armMotor = hardwareMap.get(DcMotor.class, "arm");
        }
        return instance;
    }
    
    @Override
    public void initialize() {
        // Runs on init (optional)
    }
    
    @Override
    public void periodic() {
        // Runs every loop (optional)
    }
    
    public void setPosition(int position) {
        armMotor.setTargetPosition(position);
        armMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
        armMotor.setPower(0.8);
    }
}
object ArmSubsystem : Subsystem {
    private lateinit var armMotor: DcMotor
    
    fun init(hardwareMap: HardwareMap) {
        armMotor = hardwareMap.get(DcMotor::class.java, "arm")
    }
    
    override fun initialize() {
        // Runs on init (optional)
    }
    
    override fun periodic() {
        // Runs every loop (optional)
    }
    
    fun setPosition(position: Int) {
        armMotor.targetPosition = position
        armMotor.mode = DcMotor.RunMode.RUN_TO_POSITION
        armMotor.power = 0.8
    }
}

Commands can require subsystems to prevent conflicts:

LambdaCommand command = new LambdaCommand()
    .setUpdate(() -> arm.setPosition(1000))
    .requires(arm);  // Only this command can use 'arm' at once
val command = LambdaCommand()
    .setUpdate { arm.setPosition(1000) }
    .requires(arm)  // Only this command can use 'arm' at once

OpModes

NextFTC OpModes extend NextFTCOpMode with five lifecycle functions:

@TeleOp(name = "My TeleOp")
public class MyTeleOp extends NextFTCOpMode {
    
    public MyTeleOp() {
        // Get singleton instance and register subsystem
        ArmSubsystem arm = ArmSubsystem.getInstance(hardwareMap);
        addComponents(new SubsystemComponent(arm));
    }
    
    @Override
    public void onInit() {
        // Called once when INIT is pressed
    }
    
    @Override
    public void onWaitForStart() {
        // Called repeatedly between INIT and START
    }
    
    @Override
    public void onStartButtonPressed() {
        // Called once when START is pressed
    }
    
    @Override
    public void onUpdate() {
        // Called repeatedly during TeleOp
    }
    
    @Override
    public void onStop() {
        // Called when STOP is pressed
    }
}
@TeleOp(name = "My TeleOp")
class MyTeleOp : NextFTCOpMode() {
    
    init {
        // Initialize and register singleton subsystem
        ArmSubsystem.init(hardwareMap)
        addComponents(SubsystemComponent(ArmSubsystem))
    }
    
    override fun onInit() {
        // Called once when INIT is pressed
    }
    
    override fun onWaitForStart() {
        // Called repeatedly between INIT and START
    }
    
    override fun onStartButtonPressed() {
        // Called once when START is pressed
    }
    
    override fun onUpdate() {
        // Called repeatedly during TeleOp
    }
    
    override fun onStop() {
        // Called when STOP is pressed
    }
}

Command Groups

Run commands sequentially or in parallel using helper methods:

// Sequential - one after another
Command sequential = moveArmUp
    .then(openClaw)
    .then(moveArmDown);

// Or use SequentialGroup
Command sequential2 = new SequentialGroup(moveArmUp, openClaw, moveArmDown);

// Parallel - all at once
Command parallel = driveForward
    .and(raiseArm)
    .and(spinIntake);

// Or use ParallelGroup
Command parallel2 = new ParallelGroup(driveForward, raiseArm, spinIntake);

// Race - ends when first command finishes
Command race = command1.raceWith(command2);

// Deadline - ends when deadline command finishes
Command deadline = command1.asDeadline(command2, command3);
// Sequential - one after another
val sequential = moveArmUp
    .then(openClaw)
    .then(moveArmDown)

// Or use SequentialGroup
val sequential2 = SequentialGroup(moveArmUp, openClaw, moveArmDown)

// Parallel - all at once
val parallel = driveForward
    .and(raiseArm)
    .and(spinIntake)

// Or use ParallelGroup
val parallel2 = ParallelGroup(driveForward, raiseArm, spinIntake)

// Race - ends when first command finishes
val race = command1.raceWith(command2)

// Deadline - ends when deadline command finishes
val deadline = command1.asDeadline(command2, command3)

NextBindings - Gamepad Integration

NextBindings provides a powerful button binding system. Important: Call BindingManager.update() in your onUpdate() and BindingManager.reset() in onStop().

@Override
public void onStartButtonPressed() {
    // Create buttons from gamepad inputs
    Button aButton = button(() -> gamepad1.a);
    Button bButton = button(() -> gamepad1.b);
    
    // Rising edge - triggers once when pressed
    aButton.whenBecomesTrue(() -> arm.setPosition(HIGH_POSITION));
    
    // Falling edge - triggers when released
    aButton.whenBecomesFalse(() -> arm.setPower(0));
    
    // While true - runs every loop while held
    bButton.whenTrue(() -> intake.run());
    
    // While false - runs every loop while not held
    bButton.whenFalse(() -> intake.stop());
    
    // Toggles
    button(() -> gamepad1.x)
        .toggleOnBecomesTrue()
        .whenBecomesTrue(() -> openClaw())   // First press, third press, etc.
        .whenBecomesFalse(() -> closeClaw()); // Second press, fourth press, etc.
    
    // Combine buttons with logical operators
    Button both = button(() -> gamepad1.left_bumper && gamepad1.right_bumper);
    both.whenBecomesTrue(() -> launchDrone());
}

@Override
public void onUpdate() {
    BindingManager.update();  // REQUIRED - updates all buttons
}

@Override
public void onStop() {
    BindingManager.reset();   // REQUIRED - cleanup
}
override fun onStartButtonPressed() {
    // Create buttons from gamepad inputs
    val aButton = button { gamepad1.a }
    val bButton = button { gamepad1.b }
    
    // Rising edge - triggers once when pressed
    aButton.whenBecomesTrue { arm.setPosition(HIGH_POSITION) }
    
    // Falling edge - triggers when released
    aButton.whenBecomesFalse { arm.setPower(0.0) }
    
    // While true - runs every loop while held
    bButton.whenTrue { intake.run() }
    
    // While false - runs every loop while not held
    bButton.whenFalse { intake.stop() }
    
    // Toggles
    button { gamepad1.x }
        .toggleOnBecomesTrue()
        .whenBecomesTrue { openClaw() }   // First press, third press, etc.
        .whenBecomesFalse { closeClaw() } // Second press, fourth press, etc.
    
    // Combine buttons with logical operators
    val both = button { gamepad1.left_bumper && gamepad1.right_bumper }
    both.whenBecomesTrue { launchDrone() }
}

override fun onUpdate() {
    BindingManager.update()  // REQUIRED - updates all buttons
}

override fun onStop() {
    BindingManager.reset()   // REQUIRED - cleanup
}

NextControl - Control Systems

NextControl provides a clean API for control systems with feedback and feedforward elements.

PID Control

// Create a control system with PID
ControlSystem armController = ControlSystemKt.controlSystem(builder -> {
    builder.feedback(fb -> fb.pid(0.05, 0.01, 0.004));
    return null;
});

// Use in your loop with KineticState
@Override
public void onUpdate() {
    KineticState currentState = new KineticState(
        armMotor.getCurrentPosition(),
        armMotor.getVelocity()
    );
    
    double power = armController.calculate(currentState);
    armMotor.setPower(power);
}

// Set target position
armController.setReference(1000.0);
// Create a control system with PID
val armController = controlSystem {
    posPid(0.05, 0.01, 0.004)
}

// Use in your loop with KineticState
override fun onUpdate() {
    val currentState = KineticState(
        armMotor.currentPosition.toDouble(),
        armMotor.velocity
    )
    
    val power = armController.calculate(currentState)
    armMotor.power = power
}

// Set target position
armController.goal = KineticState(1000.0)

Feedforward Control

// Arm feedforward (accounts for gravity)
ControlSystem armWithFF = ControlSystemKt.controlSystem(builder -> {
    builder.feedback(fb -> fb.pid(0.05, 0.01, 0.004));
    builder.feedforward(ff -> ff.arm(0.1, 0.5, 0.01, 0.001));  // kS, kG, kV, kA
    return null;
});

// Elevator feedforward
ControlSystem elevatorWithFF = ControlSystemKt.controlSystem(builder -> {
    builder.feedback(fb -> fb.pid(0.05, 0.01, 0.004));
    builder.feedforward(ff -> ff.elevator(0.1, 0.3, 0.01, 0.001));
    return null;
});
// Arm feedforward (accounts for gravity)
val armWithFF = controlSystem {
    posPid(0.05, 0.01, 0.004)
    armFF(0.1, 0.5, 0.01, 0.001)  // kS, kG, kV, kA
}

// Elevator feedforward
val elevatorWithFF = controlSystem {
    posPid(0.05, 0.01, 0.004)
    elevatorFF(0.1, 0.3, 0.01, 0.001)  // kS, kG, kV, kA
}

Hardware Module

Pre-built hardware commands for common tasks:

// SetPosition - move servo to position
SetPosition clawOpen = new SetPosition(clawServo, 1.0);
SetPosition clawClose = new SetPosition(clawServo, 0.0);

// Can use with multiple servos
SetPositions both = new SetPositions(
    new Pair<>(servo1, 0.5),
    new Pair<>(servo2, 0.8)
);

// Holonomic drivetrain command
HolonomicDriveCommand drive = new HolonomicDriveCommand(
    drivetrain,
    () -> -gamepad1.left_stick_y,
    () -> gamepad1.left_stick_x,
    () -> gamepad1.right_stick_x
);

// Schedule in onStartButtonPressed
CommandManager.scheduleCommand(drive);
// SetPosition - move servo to position
val clawOpen = SetPosition(clawServo, 1.0)
val clawClose = SetPosition(clawServo, 0.0)

// Can use with multiple servos
val both = SetPositions(
    servo1 to 0.5,
    servo2 to 0.8
)

// Holonomic drivetrain command
val drive = HolonomicDriveCommand(
    drivetrain,
    { -gamepad1.left_stick_y },
    { gamepad1.left_stick_x },
    { gamepad1.right_stick_x }
)

// Schedule in onStartButtonPressed
CommandManager.scheduleCommand(drive)

Complete Example OpMode

@TeleOp(name = "NextFTC TeleOp")
public class NextFTCTeleOp extends NextFTCOpMode {
    private DcMotor frontLeft, frontRight, backLeft, backRight;
    private DcMotor armMotor;
    private Servo claw;
    
    private ControlSystem armController;
    
    private static final int ARM_HIGH = 1000;
    private static final int ARM_MID = 500;
    private static final int ARM_LOW = 0;
    
    @Override
    public void onInit() {
        // Initialize hardware
        frontLeft = hardwareMap.get(DcMotor.class, "frontLeft");
        frontRight = hardwareMap.get(DcMotor.class, "frontRight");
        backLeft = hardwareMap.get(DcMotor.class, "backLeft");
        backRight = hardwareMap.get(DcMotor.class, "backRight");
        armMotor = hardwareMap.get(DcMotor.class, "arm");
        claw = hardwareMap.get(Servo.class, "claw");
        
        // Set motor directions
        frontRight.setDirection(DcMotorSimple.Direction.REVERSE);
        backRight.setDirection(DcMotorSimple.Direction.REVERSE);
        
        // Create control system with PID
        armController = ControlSystemKt.controlSystem(builder -> {
            builder.feedback(fb -> fb.pid(0.05, 0.01, 0.004));
            return null;
        });
    }
    
    @Override
    public void onStartButtonPressed() {
        // Bind gamepad controls using NextBindings
        button(() -> gamepad1.a).whenBecomesTrue(() -> armController.setReference((double) ARM_HIGH));
        button(() -> gamepad1.b).whenBecomesTrue(() -> armController.setReference((double) ARM_MID));
        button(() -> gamepad1.x).whenBecomesTrue(() -> armController.setReference((double) ARM_LOW));
        
        button(() -> gamepad1.right_bumper).whenBecomesTrue(() -> claw.setPosition(1.0));
        button(() -> gamepad1.left_bumper).whenBecomesTrue(() -> claw.setPosition(0.0));
    }
    
    @Override
    public void onUpdate() {
        // Update bindings (REQUIRED for NextBindings)
        BindingManager.update();
        
        // Mecanum drive
        double y = -gamepad1.left_stick_y;
        double x = gamepad1.left_stick_x;
        double rx = gamepad1.right_stick_x;
        
        frontLeft.setPower(y + x + rx);
        backLeft.setPower(y - x + rx);
        frontRight.setPower(y - x - rx);
        backRight.setPower(y + x - rx);
        
        // Control system for arm
        KineticState armState = new KineticState(
            armMotor.getCurrentPosition(),
            armMotor.getVelocity()
        );
        double armPower = armController.calculate(armState);
        armMotor.setPower(armPower);
        
        // Telemetry
        telemetry.addData("Arm Position", armMotor.getCurrentPosition());
        telemetry.addData("Arm Target", armController.getReference());
        telemetry.update();
    }
    
    @Override
    public void onStop() {
        BindingManager.reset();  // REQUIRED for NextBindings cleanup
    }
}
@TeleOp(name = "NextFTC TeleOp")
class NextFTCTeleOp : NextFTCOpMode() {
    private lateinit var frontLeft: DcMotor
    private lateinit var frontRight: DcMotor
    private lateinit var backLeft: DcMotor
    private lateinit var backRight: DcMotor
    private lateinit var armMotor: DcMotor
    private lateinit var claw: Servo
    
    private lateinit var armController: ControlSystem
    
    companion object {
        const val ARM_HIGH = 1000
        const val ARM_MID = 500
        const val ARM_LOW = 0
    }
    
    override fun onInit() {
        // Initialize hardware
        frontLeft = hardwareMap.get(DcMotor::class.java, "frontLeft")
        frontRight = hardwareMap.get(DcMotor::class.java, "frontRight")
        backLeft = hardwareMap.get(DcMotor::class.java, "backLeft")
        backRight = hardwareMap.get(DcMotor::class.java, "backRight")
        armMotor = hardwareMap.get(DcMotor::class.java, "arm")
        claw = hardwareMap.get(Servo::class.java, "claw")
        
        // Set motor directions
        frontRight.direction = DcMotorSimple.Direction.REVERSE
        backRight.direction = DcMotorSimple.Direction.REVERSE
        
        // Create control system with PID
        armController = controlSystem {
            posPid(0.05, 0.01, 0.004)
        }
    }
    
    override fun onStartButtonPressed() {
        // Bind gamepad controls using NextBindings
        button { gamepad1.a }.whenBecomesTrue { armController.goal = KineticState(ARM_HIGH.toDouble()) }
        button { gamepad1.b }.whenBecomesTrue { armController.goal = KineticState(ARM_MID.toDouble()) }
        button { gamepad1.x }.whenBecomesTrue { armController.goal = KineticState(ARM_LOW.toDouble()) }
        
        button { gamepad1.right_bumper }.whenBecomesTrue { claw.position = 1.0 }
        button { gamepad1.left_bumper }.whenBecomesTrue { claw.position = 0.0 }
    }
    
    override fun onUpdate() {
        // Update bindings (REQUIRED for NextBindings)
        BindingManager.update()
        
        // Mecanum drive
        val y = -gamepad1.left_stick_y
        val x = gamepad1.left_stick_x
        val rx = gamepad1.right_stick_x
        
        frontLeft.power = y + x + rx
        backLeft.power = y - x + rx
        frontRight.power = y - x - rx
        backRight.power = y + x - rx
        
        // Control system for arm
        val armState = KineticState(
            armMotor.currentPosition.toDouble(),
            armMotor.velocity
        )
        val armPower = armController.calculate(armState)
        armMotor.power = armPower
        
        // Telemetry
        telemetry.addData("Arm Position", armMotor.currentPosition)
        telemetry.addData("Arm Target", armController.goal.position)
        telemetry.update()
    }
    
    override fun onStop() {
        BindingManager.reset()  // REQUIRED for NextBindings cleanup
    }
}

Extensions

Pedro Pathing Integration

// Add the extension
implementation 'dev.nextftc:extension-pedro:1.0.1'
// Use in autonomous
FollowPath followPath = new FollowPath(follower, path);
CommandManager.scheduleCommand(followPath);
// Add the extension
implementation("dev.nextftc:extension-pedro:1.0.1")
// Use in autonomous
val followPath = FollowPath(follower, path)
CommandManager.scheduleCommand(followPath)

Road Runner Integration

// Add the extension  
implementation 'dev.nextftc:extension-roadrunner:1.0.1'
// Use with NextFTC commands
TrajectorySequenceCommand autoCmd = new TrajectorySequenceCommand(drive, trajectory);
CommandManager.scheduleCommand(autoCmd);
// Add the extension
implementation("dev.nextftc:extension-roadrunner:1.0.1")
// Use with NextFTC commands
val autoCmd = TrajectorySequenceCommand(drive, trajectory)
CommandManager.scheduleCommand(autoCmd)

Pros and Cons

Advantages:

  • ✅ Professional command-based architecture
  • ✅ Excellent built-in control systems
  • ✅ Powerful gamepad binding system
  • ✅ Hardware commands save time
  • ✅ Seamless integration between libraries
  • ✅ Active development and community
  • ✅ Great documentation at nextftc.dev

Disadvantages:

  • ❌ Learning curve for command-based programming
  • ❌ Adds dependencies to your project
  • ❌ May be overkill for simple robots
  • ❌ Different from traditional FTC structure

When to Use NextFTC

Great for:

  • Teams wanting professional code architecture
  • Complex robots with many subsystems
  • Advanced autonomous routines
  • Teams that value code organization
  • Projects using Pedro Pathing or Road Runner

Maybe skip if:

  • Simple robot with basic TeleOp only
  • Team prefers traditional FTC structure
  • Very limited programming experience
  • Want to minimize dependencies

Resources

  • Official Documentation: nextftc.dev
  • GitHub: NextFTC Organization
  • KDoc (API Reference): javadoc.io/doc/dev.nextftc
  • Discord: NextFTC Discord Server
  • Guide: Getting Started Guide

Next Steps

  1. Install NextFTC and hardware module
  2. Read the official guide at nextftc.dev
  3. Create a simple OpMode with subsystems
  4. Try NextBindings for gamepad controls
  5. Use NextControl for PID on your mechanisms
  6. Explore command groups for autonomous!

Libraries

Explore and compare popular robotics libraries like Road Runner and EasyOpenCV

Pedro Pathing

Modern path following system with smooth trajectories

On this page

What is NextFTC?Why Use NextFTC?InstallationNextFTC Core + Hardware ModuleNextControl (Optional)NextBindings (Optional)Core ConceptsCommandsSubsystemsOpModesCommand GroupsNextBindings - Gamepad IntegrationNextControl - Control SystemsPID ControlFeedforward ControlHardware ModuleComplete Example OpModeExtensionsPedro Pathing IntegrationRoad Runner IntegrationPros and ConsWhen to Use NextFTCResourcesNext Steps