Skip to content
Open
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
8 changes: 5 additions & 3 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -99,13 +99,15 @@
],
"robotJoysticks": [
{
"guid": "Keyboard0"
"guid": "78696e70757401000000000000000000",
"useGamepad": true
},
{
"guid": "Keyboard1"
"guid": "78696e70757401000000000000000000",
"useGamepad": true
},
{
"guid": "Keyboard2"
"useGamepad": true
}
]
}
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "Dreadbots2026";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 320;
public static final String GIT_SHA = "947c63f762dc7da313d3accb4446bedf85d3da40";
public static final String GIT_DATE = "2026-03-18 18:28:57 EDT";
public static final String GIT_BRANCH = "dev";
public static final String BUILD_DATE = "2026-03-27 16:31:19 EDT";
public static final long BUILD_UNIX_TIME = 1774643479924L;
public static final int GIT_REVISION = 325;
public static final String GIT_SHA = "83a38c2d2eff83be3200a6fd133e0af4775390a9";
public static final String GIT_DATE = "2026-03-28 14:28:17 EDT";
public static final String GIT_BRANCH = "Mathew-IntakeSpeedBasedOnRobotSpeed";
public static final String BUILD_DATE = "2026-04-03 18:01:51 EDT";
public static final long BUILD_UNIX_TIME = 1775253711273L;
public static final int DIRTY = 1;

private BuildConstants(){}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -143,8 +143,8 @@ public static class SlapdownConstants {
public static final double KG = 0.0;
public static final double MAX_VELOCITY = 540;
public static final double MAX_ACCELERATION = 540;
public static final int SLAPDOWN_GEARING = 1;
public static final int INTAKE_GEARING = 1;
public static final int SLAPDOWN_GEARING = 27;
public static final double INTAKE_GEARING = 1.4;
public static final double ARM_LENGTH = Units.inchesToMeters(11.75);
public static final double MIN_ANGLE_RAD = Units.degreesToRadians(-20);
public static final double MAX_ANGLE_RAD = Units.degreesToRadians(131.5);
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ public RobotContainer() {
flywheel = new Flywheel(new FlywheelIOSparkFlex(), turret);
hood = new Hood(new HoodIOSparkMax());
indexer = new Indexer(new IndexerIOSparkFlex(), operator);
slapdown = new Slapdown(new SlapdownIOSparkFlex());
slapdown = new Slapdown(new SlapdownIOSparkFlex(), drive::getChassisSpeeds);
climb = new Climb(new ClimbIOSparkFlex(), slapdown);
break;
case SIM:
Expand All @@ -120,7 +120,7 @@ public RobotContainer() {
flywheel = new Flywheel(new FlywheelIOSim(), turret);
hood = new Hood(new HoodIOSim());
indexer = new Indexer(new IndexerIOSim(), operator);
slapdown = new Slapdown(new SlapdownIOSim());
slapdown = new Slapdown(new SlapdownIOSim(), drive::getChassisSpeeds);
climb = new Climb(new ClimbIOSim(), slapdown);

break;
Expand All @@ -140,7 +140,7 @@ public RobotContainer() {
flywheel = new Flywheel(new FlywheelIOSparkFlex(), turret);
hood = new Hood(new HoodIOSparkMax());
indexer = new Indexer(new IndexerIOSparkFlex(), operator);
slapdown = new Slapdown(new SlapdownIOSparkFlex());
slapdown = new Slapdown(new SlapdownIOSparkFlex(), drive::getChassisSpeeds);
climb = new Climb(new ClimbIOSparkFlex(), slapdown);
break;
}
Expand Down
50 changes: 46 additions & 4 deletions src/main/java/frc/robot/subsystems/slapdown/Slapdown.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,17 @@
package frc.robot.subsystems.slapdown;

import java.util.function.DoubleSupplier;
import java.util.function.Supplier;

import org.littletonrobotics.junction.Logger;
import org.opencv.core.RotatedRect;

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Twist2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
Expand All @@ -13,9 +21,9 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants.SlapdownConstants;
import frc.robot.subsystems.drive.DriveConstants;

public class Slapdown extends SubsystemBase {

private final SlapdownIOInputsAutoLogged inputs = new SlapdownIOInputsAutoLogged();
private final SlapdownIO io;
public final PIDController pid = new PIDController(SlapdownConstants.KP, SlapdownConstants.KI,
Expand All @@ -34,8 +42,11 @@ public class Slapdown extends SubsystemBase {
private TrapezoidProfile.State goal = new TrapezoidProfile.State(0, 0);
private TrapezoidProfile.State setpoint = new TrapezoidProfile.State();

public Slapdown(SlapdownIO io) {
private final Supplier<ChassisSpeeds> speedsSupplier;

public Slapdown(SlapdownIO io, Supplier<ChassisSpeeds> speedsSupplier) {
this.io = io;
this.speedsSupplier = speedsSupplier;
SmartDashboard.putData("SlapdownPID", pid);
}

Expand Down Expand Up @@ -64,7 +75,7 @@ public Command intakeCommand() {
return Commands.runEnd(
() -> {
if (canRunIntake()) {
io.runIntakeVoltage(SlapdownConstants.INTAKE_VOLTAGE);
io.runIntakeVoltage(relativeIntakeSpeed());
}
},
() -> io.runIntakeVoltage(0.0)
Expand Down Expand Up @@ -143,4 +154,35 @@ public Command setAngleDegrees(double angle) {
public double getAngle() {
return inputs.absolutePosition;
}
}

public double getDotProduct() {
ChassisSpeeds speeds = speedsSupplier.get();

double xVelo = speeds.vxMetersPerSecond;
double yVelo = speeds.vyMetersPerSecond;

double dotProduct = xVelo + 0.5 * Math.abs(yVelo);
return dotProduct;
}

public double relativeIntakeSpeed() {
// i is the intake voltage
// v is the dot product range
double dotProduct = getDotProduct();
double iMin = SlapdownConstants.INTAKE_VOLTAGE/2;
double iMax = SlapdownConstants.INTAKE_VOLTAGE;
double vMin = 0;
double vMax = DriveConstants.maxSpeedMetersPerSec;;
double i;

if (dotProduct < vMin){
i = iMin;
} else if (dotProduct > vMax) {
i = iMax;
} else {
i = ((dotProduct - vMin)/(vMax - vMin))*(iMax - iMin) + iMin;
}
Logger.recordOutput("Intake/relativeVoltage", i);
return i;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ public SlapdownIOSim() {
Units.degreesToRadians(0)
);
this.intakeMotor = new DCMotorSim(
LinearSystemId.createDCMotorSystem(DCMotor.getNEO(1), SlapdownConstants.SIM_INTAKE_MOI, SlapdownConstants.INTAKE_GEARING),
DCMotor.getNEO(1)
LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), SlapdownConstants.SIM_INTAKE_MOI, SlapdownConstants.INTAKE_GEARING),
DCMotor.getKrakenX60Foc(1)
);
pivotVolts = 0.0;
intakeVolts = 0.0;
Expand Down