Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2026beta",
"projectYear": "2026",
"teamNumber": 0
}
2 changes: 1 addition & 1 deletion INSTALL.md
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ steps you need to complete:

**NOTE:** If you have any other combination of hardware (including REV NEOs,
NavX IMU, etc.) you will need to use the [YAGSL Swerve Configurator](
https://broncbotz3481.github.io/YAGSL-Example/) to configure the inputs for
https://yet-another-software-suite.github.io/YAGSL/config_generator/) to configure the inputs for
your robot. **Since the reference build recommends an all-CTRE swerve base**,
this functionality has not been extensively tested. Any teams that adopt this
method are encouraged to submit bug reports and code fixes to the [Az-RBSI
Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2026.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2026.1.1"
id "com.peterabeles.gversion" version "1.10.3"
id "com.diffplug.spotless" version "8.0.+"
id "io.freefair.lombok" version "9.1.+"
Expand Down
18 changes: 16 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
import edu.wpi.first.units.measure.Mass;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.RobotBase;
import frc.robot.AprilTagLayout.AprilTagLayoutType;
import frc.robot.FieldConstants.AprilTagLayoutType;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.SwerveConstants;
import frc.robot.util.Alert;
Expand Down Expand Up @@ -274,6 +274,14 @@ public static final class DrivebaseConstants {
public static final double kQuasiTimeout = 5.0; // seconds
public static final double kDynamicTimeout = 3.0; // seconds

// Drive motor open-loop and closed-loop ramp periods for current smoothing
// Time from from 0 -> full duty
public static final double kDriveClosedLoopRampPeriod = 0.15; // seconds
public static final double kDriveOpenLoopRampPeriod = 0.25; // seconds

public static final double kOptimalVoltage = 12.0; // Volts
public static final double kNominalFFVolts = 2.0; // Volts

// Default TalonFX Gains (Replaces what's in Phoenix X's Tuner Constants)
// NOTE: Default values from 6328's 2025 Public Code
//
Expand All @@ -282,6 +290,7 @@ public static final class DrivebaseConstants {
public static final double kDriveP = 40.0;
public static final double kDriveD = 0.03;
public static final double kDriveV = 0.83;
public static final double kDriveA = 0.0;
public static final double kDriveS = 0.21;
public static final double kDriveT =
SwerveConstants.kDriveGearRatio / DCMotor.getKrakenX60Foc(1).KtNMPerAmp;
Expand All @@ -299,6 +308,11 @@ public static final class FlywheelConstants {
// Mechanism motor gear ratio
public static final double kFlywheelGearRatio = 1.5;

// Flywheel motor open-loop and closed-loop ramp periods for current smoothing
// Time from from 0 -> full duty
public static final double kFlywheelClosedLoopRampPeriod = 0.15; // seconds
public static final double kFlywheelOpenLoopRampPeriod = 0.25; // seconds

// MODE == REAL / REPLAY
// Feedforward constants
public static final double kStaticGainReal = 0.1;
Expand Down Expand Up @@ -473,6 +487,6 @@ public static CTREPro getPhoenixPro() {

/** Get the current AprilTag layout type. */
public static AprilTagLayoutType getAprilTagLayoutType() {
return AprilTagLayout.defaultAprilTagType;
return FieldConstants.defaultAprilTagType;
}
}
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
// Copyright (c) 2024-2026 Az-FIRST
// http://github.com/AZ-First
// Copyright (c) 2025-2026 Littleton Robotics
// http://github.com/Mechanical-Advantage
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
Expand Down Expand Up @@ -28,12 +30,21 @@
import java.nio.file.Path;
import lombok.Getter;

public class AprilTagLayout {
/**
* Contains various field dimensions and useful reference points. All units are in meters and poses
* have a blue alliance origin.
*/
public class FieldConstants {

/** AprilTag Field Layout ************************************************ */
public static final double aprilTagWidth = Inches.of(6.50).in(Meters);

public static final String aprilTagFamily = "36h11";

public static final double fieldLength = AprilTagLayoutType.OFFICIAL.getLayout().getFieldLength();
public static final double fieldWidth = AprilTagLayoutType.OFFICIAL.getLayout().getFieldWidth();

public static final int aprilTagCount = AprilTagLayoutType.OFFICIAL.getLayout().getTags().size();
public static final AprilTagLayoutType defaultAprilTagType = AprilTagLayoutType.OFFICIAL;

public static final AprilTagFieldLayout aprilTagLayout =
Expand All @@ -42,34 +53,26 @@ public class AprilTagLayout {
@Getter
public enum AprilTagLayoutType {
OFFICIAL("2026-official"),

NONE("2026-none"),
REEFSCAPE("2025-official");

// SPEAKERS_ONLY("2024-speakers"),
// AMPS_ONLY("2024-amps"),
// WPI("2024-wpi");

private AprilTagLayoutType(String name) {
if (Constants.disableHAL) {
layout = null;
} else {
try {
layout =
new AprilTagFieldLayout(
Path.of(Filesystem.getDeployDirectory().getPath(), "apriltags", name + ".json"));
} catch (IOException e) {
throw new RuntimeException(e);
}
AprilTagLayoutType(String name) {
try {
layout =
new AprilTagFieldLayout(
Constants.disableHAL
? Path.of("src", "main", "deploy", "apriltags", name + ".json")
: Path.of(
Filesystem.getDeployDirectory().getPath(), "apriltags", name + ".json"));
} catch (IOException e) {
throw new RuntimeException(e);
}
if (layout == null) {
layoutString = "";
} else {
try {
layoutString = new ObjectMapper().writeValueAsString(layout);
} catch (JsonProcessingException e) {
throw new RuntimeException(
"Failed to serialize AprilTag layout JSON " + toString() + "for PhotonVision");
}

try {
layoutString = new ObjectMapper().writeValueAsString(layout);
} catch (JsonProcessingException e) {
throw new RuntimeException(
"Failed to serialize AprilTag layout JSON " + toString() + "for PhotonVision");
}
}

Expand Down
111 changes: 111 additions & 0 deletions src/main/java/frc/robot/FieldState.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,111 @@
// Copyright (c) 2026 Az-FIRST
// http://github.com/AZ-First
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// version 3 as published by the Free Software Foundation or
// available in the root directory of this project.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import frc.robot.util.Alert;

public class FieldState {

/**
* FOR 2026 - REBUILT, store the data from the FMS about the TeleOp shifts here
*
* <p>Once the FMS chooses an alliance, this value will become either 'B' or 'R' for which
* alliance's HUB is INACTIVE first.
*
* <p>If this variable is 'B', then BLUE is ACTIVE during Shift 2 and Shift 4 (and RED is ACTIVE
* during Shift 1 and Shift 3).
*
* <p>If this variable is 'R', then RED is ACTIVE during Shift 2 and Shift 4 (and BLUE is ACTIVE
* during Shift 1 and Shift 3).
*
* <p>========== TESTING ==========
*
* <p>You can test your Game Specific Data code without FMS by using the Driver Station. Click on
* the Setup tab of the Driver Station, then enter the desired test string into the Game Data text
* field. The data will be transmitted to the robot in one of two conditions: Enable the robot in
* Teleop mode, or when the DS reaches the End Game time in a Practice Match (times are
* configurable on the Setup tab). It is recommended to run at least one match using the Practice
* functionality to verify that your code works correctly in a full match flow.
*/
public static Alliance wonAuto = null;

/**
* Check whether the HUB is active right now
*
* @return Whether the team's alliance's HUB is active right now
*/
public static boolean isHubActive() {

// The HUB is active for both alliances in AUTO
if (DriverStation.isAutonomous()) {
return true;
}

// The HUB is not active when not in AUTO or TELEOP
if (!DriverStation.isTeleop()) {
return false;
}

// Read in the current match time & get alliance
// TODO: Since the ``DriverStation.getMatchTime()`` returns INT::
// Return the approximate match time. The FMS does not send an
// official match time to the robots, but does send an approximate
// match time. The value will count down the time remaining in the
// current period (auto or teleop). Warning: This is not an official
// time (so it cannot be used to dispute ref calls or guarantee that
// a function will trigger before the match ends).
double timeRemaining = DriverStation.getMatchTime();
Alliance alliance = DriverStation.getAlliance().orElse(Alliance.Blue);

// If the FMS has not provided an alliance yet, set to TRUE and kick an Alert!
if (timeRemaining < 130.0 && wonAuto == null) {
new Alert(
"No HUB data from FMS! HUB is listed as ACTIVE! Driver BEWARE!",
Alert.AlertType.WARNING)
.set(true);
return true;
}

if (timeRemaining >= 130.0) {
// TRANSITION SHIFT -- Both HUBs active
return true;

} else if (timeRemaining >= 105.0) {
// SHIFT 1 -- Non-winning alliance gets a first go
return !(wonAuto == alliance);

} else if (timeRemaining >= 80.0) {
// SHIFT 2 -- Winning alliance gets a chance
return (wonAuto == alliance);

} else if (timeRemaining >= 55.0) {
// SHIFT 3 -- Trade off
return !(wonAuto == alliance);

} else if (timeRemaining >= 30.0) {
// SHIFT 4 -- Trade off again
return (wonAuto == alliance);

} else {
// ENDGAME -- Both HUBs active
return true;
}
}
}
24 changes: 16 additions & 8 deletions src/main/java/frc/robot/README
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@ robot. The files that should exist in this directory are listed below, along
with a brief description of their contents and which files MUST be edited to
include information about the specific robot being controlled.

AprilTagLayout.java
The year-specific AprilTag and field layout file. Teams may modify this
file to include additional information specific for their needs.

BuildConstants.java
Not tracked by git, used by the build system to record information about
the latest build of the code. This file should NOT be altered, and will be
Expand All @@ -22,12 +18,24 @@ Constants.java
importing only the constants needed for a particular software module. This
file MUST be modified to include the proper robot constants in the code.

FieldConstants.java
The year-specific AprilTag and field layout file. Teams may modify the
file to include additional information specific for their needs.

FieldState.java
For 2026 - REBUILT, the field produces information that affects gameplay,
namely which HUB is active at different times during the match. The file
converts data from the FMS into data that can be used by teams for scoring
control.

Main.java
This is the file run by the RoboRIO virtual machine. Do NOT alter this
file.
The file run by the RoboRIO virtual machine. Do NOT alter this file.

README
This file.

Robot.java
This file is called by ``Main.java`` and directs the operation of the robot
The file called by ``Main.java`` and which directs the operation of the robot
according to the currently commanded mode (disabled, autonomous, teleop,
test, and simulation). Care must be taken when modifying this module to
ensure proper operation of the robot. One section that would be useful to
Expand Down Expand Up @@ -76,4 +84,4 @@ util/


--------------------
Last Modified: 06 Jan 2026, TPEB
Last Modified: 12 Jan 2026, TPEB
34 changes: 31 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
package frc.robot;

import com.revrobotics.util.StatusLogger;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Threads;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -89,8 +90,6 @@ public Robot() {
// Initialize URCL
Logger.registerURCL(URCL.startExternal());
StatusLogger.disableAutoLogging(); // Disable REVLib's built-in logging

// TODO: Uncomment this upon next release of AKit
// LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType);

// Start AdvantageKit logger
Expand Down Expand Up @@ -191,7 +190,36 @@ public void teleopInit() {

/** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}
public void teleopPeriodic() {

// For 2026 - REBUILT, the alliance will be provided as a single character
// representing the color of the alliance whose goal will go inactive
// first (i.e. ‘R’ = red, ‘B’ = blue). This alliance’s goal will be
// active in Shifts 2 and 4.
//
// https://docs.wpilib.org/en/stable/docs/yearly-overview/2026-game-data.html
if (FieldState.wonAuto == null) {
// Only call this code block if the signal from FMS has not yet arrived
String gameData = DriverStation.getGameSpecificMessage();
if (gameData.length() > 0) {
switch (gameData.charAt(0)) {
case 'B':
// Blue case code
FieldState.wonAuto = DriverStation.Alliance.Blue;
break;
case 'R':
// Red case code
FieldState.wonAuto = DriverStation.Alliance.Red;
break;
default:
// This is corrupt data, do nothing
break;
}
}
}
// Anything else for the teleopPeriodic() function

}

/** This function is called once when test mode is enabled. */
@Override
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.AprilTagLayout.AprilTagLayoutType;
import frc.robot.Constants.OperatorConstants;
import frc.robot.FieldConstants.AprilTagLayoutType;
import frc.robot.commands.AutopilotCommands;
import frc.robot.commands.DriveCommands;
import frc.robot.subsystems.accelerometer.Accelerometer;
Expand Down
Loading