Skip to content

Basic Elevator Subsystem#

A basic elevator subsystem with two motors (leader and follower), an encoder for position feedback, and limit switches for safety using motor controllers (REV SparkMax or CTRE TalonFX).

Overview#

This guide walks you through building an elevator subsystem from scratch. By the end you will have a working subsystem that can move up and down, respect limit switches, and track its position — all controlled from driver buttons.

The subsystem has two motors and two sensors:

  • Leader motor — a brushless NEO that drives the elevator up and down
  • Follower motor — a brushless NEO that mirrors the leader's movement
  • Encoder — built into the leader motor to track elevator position
  • Limit switches — DIO-connected switches at the top and bottom to prevent over-travel

See the table of contents for a breakdown of each section.


What You'll Need#

  • Two REV SparkMax motor controllers with NEO brushless motors
  • REVLib vendor dependency installed in your project
  • Two limit switches (Normally Open recommended)
  • 2 DIO ports for the limit switches

Tip

If you haven't installed REVLib yet, go to the Wpilib vendor dependency manager button on the left side. Find Revlib in the Available dependencies list and click install. If you don't see it, click the "Refresh" button at the top to fetch the latest list of libraries.

  • Two CTRE TalonFX motor controllers (brushless only)
  • Phoenix 6 vendor dependency installed in your project
  • Two limit switches (Normally Open recommended)
  • 2 DIO ports for the limit switches

Tip

If you haven't installed Phoenix 6 yet, go to the Wpilib vendor dependency manager button on the left side. Find Phoenix 6 in the Available dependencies list and click install. If you don't see it, click the "Refresh" button at the top to fetch the latest list of libraries.


The Full Example Files#

The complete subsystem code is split across three files in the same folder:

Every snippet in this guide is pulled directly from those files.


Constants#

Constants are stored in their own file, ElevatorConstants.java, placed in the same folder as the subsystem.

ElevatorConstants.java
public final class ElevatorConstants {
  // Motor IDs (SparkMax CAN IDs or TalonFX CAN IDs)
  public static final int LEADER_MOTOR_ID = 5;
  public static final int FOLLOWER_MOTOR_ID = 6;

  // Current limits
  public static final int MOTOR_CURRENT_LIMIT = 40;

  // Motor voltages for up/down movement
  public static final double UP_VOLTAGE = 8.0;
  public static final double DOWN_VOLTAGE = -8.0;

  // Limit switch DIO ports
  public static final int TOP_LIMIT_SWITCH_PORT = 2;
  public static final int BOTTOM_LIMIT_SWITCH_PORT = 3;

  // Encoder constants for the leader motor
  // This example assumes a 10:1 gear ratio and counts per revolution of encoder
  public static final double ENCODER_COUNTS_PER_REVOLUTION = 42.0; // NEO encoder CPR
  public static final double GEAR_RATIO = 10.0;
  public static final double ELEVATOR_SPROCKET_CIRCUMFERENCE = 1.432; // inches

  // Calculate distance per pulse: (circumference / CPR) * (1 / gear_ratio)
  public static final double DISTANCE_PER_PULSE =
      ELEVATOR_SPROCKET_CIRCUMFERENCE / (ENCODER_COUNTS_PER_REVOLUTION * GEAR_RATIO);

  // Position setpoints (in inches)
  public static final double ELEVATOR_MIN_HEIGHT = 0.0; // Bottom position
  public static final double ELEVATOR_MAX_HEIGHT = 48.0; // Top position
  public static final double ELEVATOR_SAFE_HEIGHT = 6.0; // Minimum height for safe operation

  private ElevatorConstants() {
    throw new UnsupportedOperationException("This is a utility class!");
  }
}

Key constants explained:

Constant Purpose
LEADER_MOTOR_ID / FOLLOWER_MOTOR_ID CAN IDs of the two SparkMax or TalonFX motors
UP_VOLTAGE / DOWN_VOLTAGE Voltages applied to move the elevator
TOP_LIMIT_SWITCH_PORT / BOTTOM_LIMIT_SWITCH_PORT DIO port numbers for the limit switches
ENCODER_COUNTS_PER_REVOLUTION Encoder CPR (42 for NEO, depends on external encoder)
GEAR_RATIO Mechanical advantage (10:1 in this example)
DISTANCE_PER_PULSE Converts encoder counts to inches of elevator travel

Note

UP_VOLTAGE and DOWN_VOLTAGE are open-loop values that apply a fixed percentage of battery voltage to the motors. They are not PID setpoints — they simply control how fast the elevator moves when you call moveUp() or moveDown(). You will likely need to adjust these based on your robot's weight and gearing.

"Positive Voltage moves the elevator up, and negative voltage moves it down." This is a common convention but may be reversed on your robot depending on wiring and motor orientation. Always test with low voltages first to confirm movement direction.

Tip

These voltage and distance values are starting points. You will almost certainly need to tune them on your real robot. Since they all live in ElevatorConstants.java, you only need to open one file when tuning.

To use the constants in BasicElevatorSubsystem.java without prefixing every value with ElevatorConstants., add a static import at the top of the subsystem file:

BasicElevatorSubsystem.java
import static frc.robot.subsystems.ElevatorConstants.*;

Declaring the Motors and Sensors#

At the class level, declare private final fields for each motor, encoder, and limit switch.

BasicElevatorSubsystem.java
public class BasicElevatorSubsystem extends SubsystemBase {
  private final SparkMax leaderMotor;
  private final SparkMax followerMotor;
  private final RelativeEncoder leaderEncoder;
  private final DigitalInput topLimitSwitch;
  private final DigitalInput bottomLimitSwitch;
BasicElevatorSubsystemTalonFX.java
public class BasicElevatorSubsystemTalonFX extends SubsystemBase {
  private final TalonFX leaderMotor;
  private final TalonFX followerMotor;
  private final DigitalInput topLimitSwitch;
  private final DigitalInput bottomLimitSwitch;

The RelativeEncoder (SparkMax) is obtained from the motor; TalonFX gets motor position directly via the Phoenix 6 API.


The Constructor#

The constructor instantiates each motor, applies configuration, sets up the follower, and initializes the limit switches.

BasicElevatorSubsystem.java
  public BasicElevatorSubsystem() {
    // Create the motors
    leaderMotor = new SparkMax(LEADER_MOTOR_ID, SparkMax.MotorType.kBrushless);
    followerMotor = new SparkMax(FOLLOWER_MOTOR_ID, SparkMax.MotorType.kBrushless);

    // Configure the leader motor with current limit
    SparkMaxConfig config = new SparkMaxConfig();
    config.smartCurrentLimit(MOTOR_CURRENT_LIMIT);
    leaderMotor.configure(config, null, null);

    // Configure the follower motor and set it to follow the leader
    followerMotor.configure(config, null, null);
    followerMotor.follow(leaderMotor);

    // Get the built-in encoder from the leader motor
    leaderEncoder = leaderMotor.getEncoder();
    leaderEncoder.setPositionConversionFactor(DISTANCE_PER_PULSE);

    // Create the limit switches
    topLimitSwitch = new DigitalInput(TOP_LIMIT_SWITCH_PORT);
    bottomLimitSwitch = new DigitalInput(BOTTOM_LIMIT_SWITCH_PORT);
  }
BasicElevatorSubsystemTalonFX.java
  public BasicElevatorSubsystemTalonFX() {
    // Create the motors
    leaderMotor = new TalonFX(LEADER_MOTOR_ID);
    followerMotor = new TalonFX(FOLLOWER_MOTOR_ID);

    // Configure with current limits
    TalonFXConfiguration config = new TalonFXConfiguration();
    config.CurrentLimits.SupplyCurrentLimit = MOTOR_CURRENT_LIMIT;
    config.CurrentLimits.SupplyCurrentLimitEnable = true;

    leaderMotor.getConfigurator().apply(config);
    followerMotor.getConfigurator().apply(config);

    // Set the follower to follow the leader
    followerMotor.setControl(new Follower(LEADER_MOTOR_ID, false));

    // Create the limit switches
    topLimitSwitch = new DigitalInput(TOP_LIMIT_SWITCH_PORT);
    bottomLimitSwitch = new DigitalInput(BOTTOM_LIMIT_SWITCH_PORT);
  }

Follower Motors

The follower motor uses follow() (SparkMax) or the Follower control class (TalonFX) to automatically mirror the leader's output. This ensures both motors provide equal force without separate control logic.

Limit Switch Initialization

Both implementations create DigitalInput objects for the limit switches. The DIO ports are specified in ElevatorConstants.java so you can adjust them easily.


Reading Sensors#

Limit Switches#

The subsystem provides methods to query limit switch state:

BasicElevatorSubsystem.java
  /**
   * Returns true if the top limit switch is pressed (elevator at max height).
   * Handles inversion so callers get the correct logical value.
   */
  public boolean isAtTopLimit() {
    return !topLimitSwitch.get();
  }

  /**
   * Returns true if the bottom limit switch is pressed (elevator at min height).
   * Handles inversion so callers get the correct logical value.
   */
  public boolean isAtBottomLimit() {
    return !bottomLimitSwitch.get();
  }
BasicElevatorSubsystemTalonFX.java
  /**
   * Returns true if the top limit switch is pressed (elevator at max height).
   * Handles inversion so callers get the correct logical value.
   */
  public boolean isAtTopLimit() {
    return !topLimitSwitch.get();
  }

  /**
   * Returns true if the bottom limit switch is pressed (elevator at min height).
   * Handles inversion so callers get the correct logical value.
   */
  public boolean isAtBottomLimit() {
    return !bottomLimitSwitch.get();
  }

Both methods return true when the elevator is at that limit. They invert the raw switch reading because limit switches are wired as Normally Open (NO) — they read false when pressed.

Position Tracking#

BasicElevatorSubsystem.java
  /**
   * Returns the current height of the elevator in inches.
   */
  public double getPosition() {
    return leaderEncoder.getPosition();
  }

  /**
   * Resets the encoder to zero (at current position).
   */
  public void resetPosition() {
    leaderEncoder.setPosition(0.0);
  }
BasicElevatorSubsystemTalonFX.java
  /**
   * Returns the current height of the elevator in rotations.
   * TalonFX rotor position is in rotations; convert to inches if needed
   * using the DISTANCE_PER_PULSE constant.
   */
  public double getPosition() {
    return leaderMotor.getPosition().getValueAsDouble() * DISTANCE_PER_PULSE;
  }

  /**
   * Resets the encoder to zero (at current position).
   */
  public void resetPosition() {
    leaderMotor.setPosition(0.0);
  }

getPosition() returns the elevator height in inches, calculated from encoder data. resetPosition() zeroes the encoder at the current location — useful for calibration.

TalonFX Encoder Conversion

TalonFX reports rotor position in rotations. To convert to inches, multiply by DISTANCE_PER_PULSE, which accounts for the gear ratio and mechanism circumference.


Elevator Movement Methods#

These methods handle safe movement by checking limit switches before applying voltage:

BasicElevatorSubsystem.java
  /**
   * Moves the elevator up at constant voltage.
   * Stops if the top limit switch is pressed.
   */
  public void moveUp() {
    if (!isAtTopLimit()) {
      leaderMotor.setVoltage(UP_VOLTAGE);
    } else {
      stop();
    }
  }

  /**
   * Moves the elevator down at constant voltage.
   * Stops if the bottom limit switch is pressed.
   */
  public void moveDown() {
    if (!isAtBottomLimit()) {
      leaderMotor.setVoltage(DOWN_VOLTAGE);
    } else {
      stop();
    }
  }

  /**
   * Stops the elevator.
   */
  public void stop() {
    leaderMotor.setVoltage(0.0);
  }
BasicElevatorSubsystemTalonFX.java
  /**
   * Moves the elevator up at constant voltage.
   * Stops if the top limit switch is pressed.
   */
  public void moveUp() {
    if (!isAtTopLimit()) {
      leaderMotor.setVoltage(UP_VOLTAGE);
    } else {
      stop();
    }
  }

  /**
   * Moves the elevator down at constant voltage.
   * Stops if the bottom limit switch is pressed.
   */
  public void moveDown() {
    if (!isAtBottomLimit()) {
      leaderMotor.setVoltage(DOWN_VOLTAGE);
    } else {
      stop();
    }
  }

  /**
   * Stops the elevator.
   */
  public void stop() {
    leaderMotor.setVoltage(0.0);
  }
  • moveUp() — applies positive voltage unless the top limit switch is pressed
  • moveDown() — applies negative voltage unless the bottom limit switch is pressed
  • stop() — applies zero voltage to hold the elevator in place

Safety First

The limit-check logic prevents mechanical over-travel. Always include these guards in real robot code to protect mechanism and hardware.


Command Factories#

WPILib's command-based framework lets you convert subsystem methods into Command objects that the scheduler can run, interrupt, and chain together. These commands are usually bound to controller buttons in RobotContainer.java.

BasicElevatorSubsystem.java
  /**
   * A command that moves the elevator up.
   * The command runs continuously, checking limit switches each loop.
   */
  public Command moveUpCommand() {
    return this.run(this::moveUp);
  }

  /**
   * A command that moves the elevator down.
   * The command runs continuously, checking limit switches each loop.
   */
  public Command moveDownCommand() {
    return this.run(this::moveDown);
  }

  /**
   * A command that stops the elevator.
   * This is useful as a default command.
   */
  public Command stopCommand() {
    return this.runOnce(this::stop);
  }
BasicElevatorSubsystemTalonFX.java
  /**
   * A command that moves the elevator up.
   * The command runs continuously, checking limit switches each loop.
   */
  public Command moveUpCommand() {
    return this.run(this::moveUp);
  }

  /**
   * A command that moves the elevator down.
   * The command runs continuously, checking limit switches each loop.
   */
  public Command moveDownCommand() {
    return this.run(this::moveDown);
  }

  /**
   * A command that stops the elevator.
   * This is useful as a default command.
   */
  public Command stopCommand() {
    return this.runOnce(this::stop);
  }
  • moveUpCommand() — returns a run() command that calls moveUp() every loop
  • moveDownCommand() — returns a run() command that calls moveDown() every loop
  • stopCommand() — returns a runOnce() command that calls stop() once and immediately finishes

run() vs runOnce()

  • run() calls the lambda every robot loop (20 ms) while the command is scheduled
  • runOnce() calls the lambda once and then immediately finishes

Use run() for continuous movement and runOnce() for one-time actions.


Hooking It Up in RobotContainer#

Instantiate the subsystem and bind buttons in RobotContainer.java. See the WPILib docs on binding commands to triggers for more options.

Instantiate the Subsystem#

RobotContainer.java
private final BasicElevatorSubsystem m_elevator = new BasicElevatorSubsystem();

Set a Default Command#

Set stopCommand() as the default so motors turn off whenever no button is held:

RobotContainer.java
m_elevator.setDefaultCommand(m_elevator.stopCommand());

Bind Buttons#

A typical setup binds up/down movement to Xbox controller bumpers:

RobotContainer.java
// Hold right trigger to move elevator up
driverController.rightTrigger()
    .whileTrue(m_elevator.moveUpCommand());

// Hold left trigger to move elevator down
driverController.leftTrigger()
    .whileTrue(m_elevator.moveDownCommand());

whileTrue()

whileTrue() schedules the command while the trigger condition is true and cancels it (triggering the default command) when false. This means the elevator automatically stops when the driver lets go.


Next Steps#

  • Add PID control — move to specific setpoints (e.g., "raise to 24 inches") using closed-loop feedback from the encoder. see PID_elevator for more information.
  • Add telemetry — log position and limit switch state to SmartDashboard for tuning
  • Integrate into game logic — use the elevator in autonomous sequences or more complex command chains
  • Tune constants — adjust voltages, distance calculations, and gear ratios based on real robot behavior

See the WPILib documentation for advanced control topics like PID and state machine designs.