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
7 changes: 1 addition & 6 deletions .github/workflows/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,10 @@ jobs:
# This workflow contains a single job called "build"
build:
# The type of runner that the job will run on
runs-on: ubuntu-latest
runs-on: ubuntu-24.04

# This grabs the WPILib docker container
container: wpilib/roborio-cross-ubuntu:2025-24.04

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
Expand All @@ -29,10 +28,6 @@ jobs:
- name: Add repository to git safe directories
run: git config --global --add safe.directory $GITHUB_WORKSPACE

# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
run: chmod +x gradlew

# Runs a single command using the runners shell
- name: Compile and run tests on robot code
run: ./gradlew build
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.3.2"
id "com.diffplug.spotless" version "6.20.0"
id "com.gorylenko.gradle-git-properties" version '2.5.0'
id "com.gorylenko.gradle-git-properties" version '2.5.1'
}

gitProperties {
Expand Down
3 changes: 2 additions & 1 deletion gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-9.2.1-bin.zip
distributionSha256Sum=72f44c9f8ebcb1af43838f45ee5c4aa9c5444898b3468ab3f4af7b6076c5bc3f
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME
Expand Down
27 changes: 14 additions & 13 deletions src/main/java/com/team6962/lib/digitalsensor/BeamBreak.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,22 @@
import edu.wpi.first.wpilibj.Timer;

public class BeamBreak extends DigitalSensor {
private double simulatedDetectionTime;
private double lastDetectionTimestamp;
private double simulatedDetectionTime;
private double lastDetectionTimestamp;

public BeamBreak(int channel, DigitalSensor.Wiring wiring, Time simulatedDetectionTime) {
super(channel, wiring);
public BeamBreak(int channel, DigitalSensor.Wiring wiring, Time simulatedDetectionTime) {
super(channel, wiring);

this.simulatedDetectionTime = simulatedDetectionTime.in(Seconds);
}
this.simulatedDetectionTime = simulatedDetectionTime.in(Seconds);
}

@Override
public void simulationPeriodic() {
setTriggeredInSimulation(Timer.getFPGATimestamp() - lastDetectionTimestamp < simulatedDetectionTime);
}
@Override
public void simulationPeriodic() {
setTriggeredInSimulation(
Timer.getFPGATimestamp() - lastDetectionTimestamp < simulatedDetectionTime);
}

public void simulateDetection() {
lastDetectionTimestamp = Timer.getFPGATimestamp();
}
public void simulateDetection() {
lastDetectionTimestamp = Timer.getFPGATimestamp();
}
}
60 changes: 30 additions & 30 deletions src/main/java/com/team6962/lib/digitalsensor/DigitalSensor.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,43 +5,43 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class DigitalSensor extends SubsystemBase {
private DigitalInput input;
private Wiring wiring;
private boolean triggeredSim;

public DigitalSensor(int channel, Wiring wiring) {
input = new DigitalInput(channel);
this.wiring = wiring;
private DigitalInput input;
private Wiring wiring;
private boolean triggeredSim;

public DigitalSensor(int channel, Wiring wiring) {
input = new DigitalInput(channel);
this.wiring = wiring;
}

public boolean isTriggered() {
if (RobotBase.isSimulation()) {
return triggeredSim;
}

public boolean isTriggered() {
if (RobotBase.isSimulation()) {
return triggeredSim;
}

return input.get() == wiring.triggeredValue;
}
return input.get() == wiring.triggeredValue;
}

public boolean notTriggered() {
return !isTriggered();
}
public boolean notTriggered() {
return !isTriggered();
}

public void setTriggeredInSimulation(boolean triggered) {
this.triggeredSim = triggered;
}
public void setTriggeredInSimulation(boolean triggered) {
this.triggeredSim = triggered;
}

public static enum Wiring {
NormallyOpen(false),
NormallyClosed(true);
public static enum Wiring {
NormallyOpen(false),
NormallyClosed(true);

private boolean triggeredValue;
private boolean triggeredValue;

private Wiring(boolean triggeredValue) {
this.triggeredValue = triggeredValue;
}
private Wiring(boolean triggeredValue) {
this.triggeredValue = triggeredValue;
}

public boolean getValueWhenDetecting() {
return triggeredValue;
}
public boolean getValueWhenDetecting() {
return triggeredValue;
}
}
}
1 change: 0 additions & 1 deletion src/main/java/com/team6962/lib/swerve/SwerveConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
import com.team6962.lib.swerve.module.SwerveModule.Corner;
import com.team6962.lib.utils.KinematicsUtils;
import com.team6962.lib.utils.MeasureMath;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.system.plant.DCMotor;
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/com/team6962/lib/swerve/SwerveCore.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ public SwerveCore(SwerveConfig constants) {

kinematics = KinematicsUtils.kinematicsFromChassis(constants.chassis());
poseEstimator =
new PoseEstimator(kinematics, () -> getModulePositions(), () -> getModuleStates(), constants);
new PoseEstimator(
kinematics, () -> getModulePositions(), () -> getModuleStates(), constants);

currentMovement = new SpeedsMovement();

Expand Down
145 changes: 76 additions & 69 deletions src/main/java/com/team6962/lib/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,6 @@
import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.Seconds;

import java.util.List;
import java.util.Set;
import java.util.function.Supplier;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.commands.FollowPathCommand;
import com.pathplanner.lib.config.PIDConstants;
Expand All @@ -34,7 +30,6 @@
import com.team6962.lib.utils.CommandUtils;
import com.team6962.lib.utils.KinematicsUtils;
import com.team6962.lib.utils.MeasureMath;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Pose2d;
Expand All @@ -57,6 +52,9 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.List;
import java.util.Set;
import java.util.function.Supplier;

/**
* The main class for the swerve drive system. This class extends {@link SwerveCore} to provide the
Expand Down Expand Up @@ -561,9 +559,11 @@ public Command driveTwist(Supplier<Twist2d> twist) {

public Command drivePreciselyTo(Pose2d targetPose) {
return driveTwist(() -> getEstimatedPose().log(targetPose))
.deadlineFor(Commands.run(() -> {
Logger.getField().getObject("Target Pose").setPose(targetPose);
}));
.deadlineFor(
Commands.run(
() -> {
Logger.getField().getObject("Target Pose").setPose(targetPose);
}));
}

private class ProfiledDriveCommand extends Command {
Expand All @@ -573,9 +573,9 @@ private class ProfiledDriveCommand extends Command {
private double startTime;

public ProfiledDriveCommand(
HolonomicPositionController.State targetState, // TODO: Convert to supplier or make wrapper methods use Commands.defer
HolonomicPositionController controller
) {
HolonomicPositionController.State
targetState, // TODO: Convert to supplier or make wrapper methods use Commands.defer
HolonomicPositionController controller) {
this.targetState = targetState;
this.controller = controller;

Expand Down Expand Up @@ -611,52 +611,57 @@ public boolean isFinished() {

@Override
public void end(boolean interrupted) {
controller.close();
controller.close();
}
}

public Command driveQuicklyTo(HolonomicPositionController.State targetState, LinearVelocity maxVelocity) {
return new ProfiledDriveCommand(targetState, new HolonomicPositionController(
new TrapezoidProfile.Constraints(
maxVelocity.in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2)
))
.deadlineFor(Commands.run(() -> {
Logger.getField().getObject("Target Pose").setPose(targetState.position);
}));
public Command driveQuicklyTo(
HolonomicPositionController.State targetState, LinearVelocity maxVelocity) {
return new ProfiledDriveCommand(
targetState,
new HolonomicPositionController(
new TrapezoidProfile.Constraints(
maxVelocity.in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2)))
.deadlineFor(
Commands.run(
() -> {
Logger.getField().getObject("Target Pose").setPose(targetState.position);
}));
}

public Command driveQuicklyTo(Pose2d targetPose, ChassisSpeeds targetSpeeds, LinearVelocity maxVelocity) {
return driveQuicklyTo(new HolonomicPositionController.State(targetPose, targetSpeeds), maxVelocity);
public Command driveQuicklyTo(
Pose2d targetPose, ChassisSpeeds targetSpeeds, LinearVelocity maxVelocity) {
return driveQuicklyTo(
new HolonomicPositionController.State(targetPose, targetSpeeds), maxVelocity);
}

public Command driveQuicklyTo(Pose2d targetPose, LinearVelocity maxVelocity) {
return driveQuicklyTo(targetPose, new ChassisSpeeds(), maxVelocity);
}

public Command driveQuicklyTo(HolonomicPositionController.State targetState) {
return new ProfiledDriveCommand(targetState, new HolonomicPositionController(
new TrapezoidProfile.Constraints(
getConstants().maxDriveSpeed().in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2)
))
.deadlineFor(Commands.run(() -> {
Logger.getField().getObject("Target Pose").setPose(targetState.position);
}));
return new ProfiledDriveCommand(
targetState,
new HolonomicPositionController(
new TrapezoidProfile.Constraints(
getConstants().maxDriveSpeed().in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2)))
.deadlineFor(
Commands.run(
() -> {
Logger.getField().getObject("Target Pose").setPose(targetState.position);
}));
}

public Command driveQuicklyTo(Pose2d targetPose, ChassisSpeeds targetSpeeds) {
Expand All @@ -668,40 +673,42 @@ public Command driveQuicklyTo(Pose2d targetPose) {
}

public Command driveQuicklyToState(Supplier<HolonomicPositionController.State> targetState) {
ProfiledDriveCommand profiledDriveCommand = new ProfiledDriveCommand(targetState.get(), new HolonomicPositionController(
new TrapezoidProfile.Constraints(
getConstants().maxDriveSpeed().in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)
),
new PIDConstraints(1.0, 0.0, 0.2)
));

return profiledDriveCommand.deadlineFor(Commands.run(() -> {
profiledDriveCommand.setTarget(targetState.get());
Logger.getField().getObject("Target Pose").setPose(targetState.get().position);
}));
ProfiledDriveCommand profiledDriveCommand =
new ProfiledDriveCommand(
targetState.get(),
new HolonomicPositionController(
new TrapezoidProfile.Constraints(
getConstants().maxDriveSpeed().in(MetersPerSecond),
getConstants().maxLinearAcceleration().in(MetersPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2),
new TrapezoidProfile.Constraints(
getConstants().maxRotationSpeed().in(RadiansPerSecond),
getConstants().maxAngularAcceleration().in(RadiansPerSecondPerSecond)),
new PIDConstraints(1.0, 0.0, 0.2)));

return profiledDriveCommand.deadlineFor(
Commands.run(
() -> {
profiledDriveCommand.setTarget(targetState.get());
Logger.getField().getObject("Target Pose").setPose(targetState.get().position);
}));
}

public Command driveQuicklyTo(Supplier<Pose2d> targetPose, Supplier<ChassisSpeeds> targetSpeeds) {
return driveQuicklyToState(() -> new HolonomicPositionController.State(targetPose.get(), targetSpeeds.get()));
return driveQuicklyToState(
() -> new HolonomicPositionController.State(targetPose.get(), targetSpeeds.get()));
}

public Command driveQuicklyTo(Supplier<Pose2d> targetPose) {
return driveQuicklyToState(() -> new HolonomicPositionController.State(targetPose.get(), new ChassisSpeeds()));
return driveQuicklyToState(
() -> new HolonomicPositionController.State(targetPose.get(), new ChassisSpeeds()));
}

public Command driveTo(Pose2d targetPose, ChassisSpeeds targetSpeeds) {
return Commands.either(
drivePreciselyTo(targetPose),
driveQuicklyTo(targetPose, targetSpeeds)
.andThen(drivePreciselyTo(targetPose)),
() -> isWithinToleranceOf(targetPose, Inches.of(15), Degrees.of(30))
);
drivePreciselyTo(targetPose),
driveQuicklyTo(targetPose, targetSpeeds).andThen(drivePreciselyTo(targetPose)),
() -> isWithinToleranceOf(targetPose, Inches.of(15), Degrees.of(30)));
}

public Command driveTo(Pose2d targetPose) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.Constants.LIMELIGHT;
import frc.robot.vision.AprilTags;

import java.util.function.Supplier;

/**
Expand Down
Loading