Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Abigail swrve x stance #12

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
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
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
# This gitignore has been specially created by the WPILib team.
# If you remove items from this file, intellisense might break.
*src/main/java/frc/robot/BuildConstants.java
simgui-ds.json
simgui.json
networktables.json
### C++ ###
# Prerequisites
*.d
Expand Down
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": "2025beta",
"projectYear": "2025",
"teamNumber": 4829
}
34 changes: 17 additions & 17 deletions 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 "2025.1.1-beta-3"
id "edu.wpi.first.GradleRIO" version "2025.1.1"
id "com.peterabeles.gversion" version "1.10"
id "com.diffplug.spotless" version "6.25.0"
id "pmd"
Expand Down Expand Up @@ -66,21 +66,21 @@ wpi.java.debugJni = false
def includeDesktopSupport = true

// Configuration for AdvantageKit
repositories {
maven {
url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
credentials {
username = "Mechanical-Advantage-Bot"
password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
}
}
mavenLocal()
}
// repositories {
// maven {
// url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
// credentials {
// username = "Mechanical-Advantage-Bot"
// password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
// }
// }
// mavenLocal()
// }

task(replayWatch, type: JavaExec) {
mainClass = "org.littletonrobotics.junction.ReplayWatch"
classpath = sourceSets.main.runtimeClasspath
}
// task(replayWatch, type: JavaExec) {
// mainClass = "org.littletonrobotics.junction.ReplayWatch"
// classpath = sourceSets.main.runtimeClasspath
// }

// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 4.
Expand Down Expand Up @@ -108,8 +108,8 @@ dependencies {
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'

def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
annotationProcessor "org.littletonrobotics.akit:akit-autolog:$akitJson.version"
// def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
// annotationProcessor "org.littletonrobotics.akit:akit-autolog:$akitJson.version"
}

test {
Expand Down
Empty file modified gradlew
100644 → 100755
Empty file.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
import frc.robot.subsystems.swerve.module.PhysicalModule;
import frc.robot.subsystems.swerve.module.SimulatedModule;
import frc.robot.subsystems.vision.PhysicalVision;
import frc.robot.subsystems.vision.SimulatedVision;
// import frc.robot.subsystems.vision.SimulatedVision;
import frc.robot.subsystems.vision.VisionInterface;
import frc.robot.subsystems.vision.VisionSubsystem;
import java.util.function.DoubleSupplier;
Expand Down Expand Up @@ -107,9 +107,9 @@
new SimulatedModule(swerveDriveSimulation.getModules()[2]),
new SimulatedModule(swerveDriveSimulation.getModules()[3]));

visionSubsystem =
new VisionSubsystem(
new SimulatedVision(() -> swerveDriveSimulation.getSimulatedDriveTrainPose()));
visionSubsystem = null;
// new VisionSubsystem(
// new SimulatedVision(() -> swerveDriveSimulation.getSimulatedDriveTrainPose()));

SimulatedField.getInstance().resetFieldForAuto();
resetFieldAndOdometryForAuto(
Expand Down Expand Up @@ -171,12 +171,12 @@
() -> JoystickUtil.modifyAxisPolar(driverLeftStickX, driverLeftStickY, 3)[1]
};

DoubleSupplier operatorLeftStickX = operatorController::getLeftX;

Check warning on line 174 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorLeftStickX'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 174 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorLeftStickX'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
DoubleSupplier operatorRightStickY = operatorController::getRightY;

Check warning on line 175 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorRightStickY'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 175 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'operatorRightStickY'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Trigger driverRightBumper = new Trigger(driverController.rightBumper());
Trigger driverRightDirectionPad = new Trigger(driverController.pov(90));
Trigger driverDownDirectionPad = new Trigger(driverController.pov(180));

Check warning on line 179 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverDownDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable

Check warning on line 179 in src/main/java/frc/robot/RobotContainer.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused local variables such as 'driverDownDirectionPad'.

Detects when a local variable is declared and/or assigned, but not used. Variables whose name starts with `ignored` or `unused` are filtered out. UnusedLocalVariable (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedlocalvariable
Trigger driverLeftDirectionPad = new Trigger(driverController.pov(270));

// // autodrive
Expand Down
11 changes: 10 additions & 1 deletion src/main/java/frc/robot/commands/drive/DriveCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,25 @@

import frc.robot.subsystems.swerve.SwerveConstants.DriveConstants;
import frc.robot.subsystems.swerve.SwerveDrive;
import frc.robot.subsystems.swerve.gyro.GyroInterface;
import frc.robot.subsystems.swerve.module.ModuleInterface;
import frc.robot.subsystems.vision.VisionSubsystem;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import com.ctre.phoenix6.swerve.SwerveModule;

import edu.wpi.first.math.geometry.Rotation2d;

// import frc.robot.subsystems.vision.VisionSubsystem;

public class DriveCommand extends DriveCommandBase {

private final SwerveDrive driveSubsystem;

private final DoubleSupplier leftJoystickY, leftJoystickX, rightJoystickX;

Check warning on line 21 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Use one line for each declaration, it enhances code readability.

Java allows the use of several variables declaration of the same type on one line. However, it can lead to quite messy code. This rule looks for several declarations on the same line. OneDeclarationPerLine (Priority: 4, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#onedeclarationperline

Check warning on line 21 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Use one line for each declaration, it enhances code readability.

Java allows the use of several variables declaration of the same type on one line. However, it can lead to quite messy code. This rule looks for several declarations on the same line. OneDeclarationPerLine (Priority: 4, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#onedeclarationperline
private final BooleanSupplier isFieldRelative, isHighRotation;

Check warning on line 22 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Use one line for each declaration, it enhances code readability.

Java allows the use of several variables declaration of the same type on one line. However, it can lead to quite messy code. This rule looks for several declarations on the same line. OneDeclarationPerLine (Priority: 4, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#onedeclarationperline

Check warning on line 22 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Use one line for each declaration, it enhances code readability.

Java allows the use of several variables declaration of the same type on one line. However, it can lead to quite messy code. This rule looks for several declarations on the same line. OneDeclarationPerLine (Priority: 4, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#onedeclarationperline
private double angularSpeed;

Check warning on line 23 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Perhaps 'angularSpeed' could be replaced by a local variable.

Reports fields which may be converted to a local variable. This is so because in every method where the field is used, it is assigned before it is first read. Hence, the value that the field had before the method call may not be observed, so it might as well not be stored in the enclosing object. Limitations: * We can only check private fields for now. * The rule is not aware of threading, so it may cause false positives in concurrent code. Such FPs are best handled by suppression (see also the `ignoredAnnotations` property). SingularField (Priority: 3, Ruleset: Design) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_design.html#singularfield

Check warning on line 23 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Perhaps 'angularSpeed' could be replaced by a local variable.

Reports fields which may be converted to a local variable. This is so because in every method where the field is used, it is assigned before it is first read. Hence, the value that the field had before the method call may not be observed, so it might as well not be stored in the enclosing object. Limitations: * We can only check private fields for now. * The rule is not aware of threading, so it may cause false positives in concurrent code. Such FPs are best handled by suppression (see also the `ignoredAnnotations` property). SingularField (Priority: 3, Ruleset: Design) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_design.html#singularfield

/**
* The command for driving the robot using joystick inputs.
Expand All @@ -29,6 +35,7 @@
*/
public DriveCommand(
SwerveDrive driveSubsystem,
SwerveModule swerveModule,

Check warning on line 38 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused constructor parameters such as 'swerveModule'.

Reports parameters of methods and constructors that are not referenced them in the method body. Parameters whose name starts with `ignored` or `unused` are filtered out. Removing unused formal parameters from public methods could cause a ripple effect through the code base. Hence, by default, this rule only considers private methods. To include non-private methods, set the `checkAll` property to `true`. UnusedFormalParameter (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedformalparameter

Check warning on line 38 in src/main/java/frc/robot/commands/drive/DriveCommand.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid unused constructor parameters such as 'swerveModule'.

Reports parameters of methods and constructors that are not referenced them in the method body. Parameters whose name starts with `ignored` or `unused` are filtered out. Removing unused formal parameters from public methods could cause a ripple effect through the code base. Hence, by default, this rule only considers private methods. To include non-private methods, set the `checkAll` property to `true`. UnusedFormalParameter (Priority: 3, Ruleset: Best Practices) https://docs.pmd-code.org/pmd-doc-7.9.0/pmd_rules_java_bestpractices.html#unusedformalparameter
VisionSubsystem visionSubsystem,
DoubleSupplier leftJoystickY,
DoubleSupplier leftJoystickX,
Expand Down Expand Up @@ -68,7 +75,9 @@
}

@Override
public void end(boolean interrupted) {}
public void end(boolean interrupted) {
angularSpeed = 0;
}

@Override
public boolean isFinished() {
Expand Down
37 changes: 37 additions & 0 deletions src/main/java/frc/robot/commands/drive/XSwerve.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If ur not gonna use this plz delete

// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.drive;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.swerve.SwerveConstants;

/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class XSwerve extends Command {
/** Creates a new XSwerve. */
public XSwerve() {
SwerveConstants swerveConstants;
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
if
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/subsystems/swerve/SwerveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@ public static final class DriveConstants {
public static final int REAR_LEFT_CANCODER_ID = 11;
public static final int REAR_RIGHT_CANCODER_ID = 13;

public static final double FRONT_LEFT_ZERO_ANGLE = 0.137939453125;
public static final double FRONT_RIGHT_ZERO_ANGLE = -0.420654296875;
public static final double REAR_LEFT_ZERO_ANGLE = -0.475341796875;
public static final double REAR_RIGHT_ZERO_ANGLE = -0.05078125;
public static final double FRONT_LEFT_ZERO_ANGLE = 0.0;
public static final double FRONT_RIGHT_ZERO_ANGLE = 0;
public static final double REAR_LEFT_ZERO_ANGLE = 0;
public static final double REAR_RIGHT_ZERO_ANGLE = 0;

public static final SensorDirectionValue FRONT_LEFT_CANCODER_REVERSED =
SensorDirectionValue.CounterClockwise_Positive;
Expand Down Expand Up @@ -103,9 +103,9 @@ public class ModuleConstants {
public static final double DRIVE_SUPPLY_LIMIT = 45.0;
public static final double DRIVE_STATOR_LIMIT = 50.0;

public static final double TURN_P = 116;
public static final double TURN_P = 0;
public static final double TURN_I = 0.0;
public static final double TURN_D = 0.64;
public static final double TURN_D = 0.0;

public static final double TURN_S = 0.0;
public static final double TURN_V = 0.0;
Expand All @@ -114,18 +114,18 @@ public class ModuleConstants {
public static final double MAX_ANGULAR_SPEED_ROTATIONS_PER_SECOND = 30;
public static final double MAX_ANGULAR_ACCELERATION_ROTATIONS_PER_SECOND_SQUARED = 24;

public static final double DRIVE_P = 0.417;
public static final double DRIVE_P = 0.0;
public static final double DRIVE_I = 0.0;
public static final double DRIVE_D = 0.0;

public static final double DRIVE_S = 0.16;
public static final double DRIVE_S = 0.0;
// These values were gotten using recalc, then converted to the correct units & were confirmed
// through testing and characterization
// https://www.reca.lc/drive?appliedVoltageRamp=%7B%22s%22%3A1200%2C%22u%22%3A%22V%2Fs%22%7D&batteryAmpHours=%7B%22s%22%3A18%2C%22u%22%3A%22A%2Ah%22%7D&batteryResistance=%7B%22s%22%3A0.018%2C%22u%22%3A%22Ohm%22%7D&batteryVoltageAtRest=%7B%22s%22%3A12.6%2C%22u%22%3A%22V%22%7D&efficiency=97&filtering=1&gearRatioMax=%7B%22magnitude%22%3A15%2C%22ratioType%22%3A%22Reduction%22%7D&gearRatioMin=%7B%22magnitude%22%3A3%2C%22ratioType%22%3A%22Reduction%22%7D&maxSimulationTime=%7B%22s%22%3A4%2C%22u%22%3A%22s%22%7D&maxSpeedAccelerationThreshold=%7B%22s%22%3A0.15%2C%22u%22%3A%22ft%2Fs2%22%7D&motor=%7B%22quantity%22%3A4%2C%22name%22%3A%22Kraken%20X60%2A%22%7D&motorCurrentLimit=%7B%22s%22%3A60%2C%22u%22%3A%22A%22%7D&numCyclesPerMatch=24&peakBatteryDischarge=20&ratio=%7B%22magnitude%22%3A4.59%2C%22ratioType%22%3A%22Reduction%22%7D&sprintDistance=%7B%22s%22%3A25%2C%22u%22%3A%22ft%22%7D&swerve=1&targetTimeToGoal=%7B%22s%22%3A2%2C%22u%22%3A%22s%22%7D&throttleResponseMax=0.99&throttleResponseMin=0.5&weightAuxilliary=%7B%22s%22%3A24%2C%22u%22%3A%22lbs%22%7D&weightDistributionFrontBack=0.5&weightDistributionLeftRight=0.5&weightInspected=%7B%22s%22%3A125%2C%22u%22%3A%22lbs%22%7D&wheelBaseLength=%7B%22s%22%3A27%2C%22u%22%3A%22in%22%7D&wheelBaseWidth=%7B%22s%22%3A20%2C%22u%22%3A%22in%22%7D&wheelCOFDynamic=0.9&wheelCOFLateral=1.1&wheelCOFStatic=1.1&wheelDiameter=%7B%22s%22%3A4%2C%22u%22%3A%22in%22%7D
public static final double DRIVE_V =
1.73 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.1203 V*s/m
public static final double DRIVE_A =
0.32 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.02225 V*s^2/m
public static final double DRIVE_V = 0;
// 1.73 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.1203 V*s/m
public static final double DRIVE_A = 0;
// 0.32 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.02225 V*s^2/m
}

public static final class TrajectoryConstants {
Expand Down
30 changes: 29 additions & 1 deletion src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
import java.util.Optional;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import java.util.Timer;
import java.util.TimerTask;

public class SwerveDrive extends SubsystemBase {
private final GyroInterface gyroIO;
Expand Down Expand Up @@ -276,8 +278,34 @@ public Rotation2d getOdometryAllianceRelativeRotation2d() {
public void setModuleStates(SwerveModuleState[] desiredStates) {
for (int i = 0; i < 4; i++) {
swerveModules[i].runSetPoint((desiredStates[i]));
}
}
}

private boolean isMoving; // Tracks if the robot is moving
private long lastMovementTime = System.currentTimeMillis(); // Time of the last movement
private static final long INACTIVITY_THRESHOLD = 3000; // 3 seconds in milliseconds

// Check if the robot has been inactive for 3 seconds
public boolean threesecsinactive() {
if (!isMoving && System.currentTimeMillis() - lastMovementTime >= INACTIVITY_THRESHOLD) {
return true; // 3 seconds of inactivity
}
return false; // Still moving or not enough time passed
}

public void setXStance(SwerveModuleState[] xState) {
isMoving = false;
if (threesecsinactive()) { // Only lock if inactive for 3 seconds
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

honestly this not rlly the best way of doing it. also the setXStance isn't used anywhere sooooooooo it wouldn't actually happen.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

imo u could use wpilib's timer or the fpga clock and get if some amount of time has passed.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

u might want to separate the if statement out of the method bc we want the thing that does the xStance to be usable in other contexts. In addition, we might also make it a button, so another reason to move the if statement out.

If you want to do the three seconds (which we might do) you could maybe put it in something like setModuleStates or drive?

Rotation2d[] swerveHeadings = new Rotation2d[swerveModules.length];
for (int i = 0; i < swerveHeadings.length; i++) {
swerveHeadings[i] = swerveModules[i].getPosition().angle;
}
DriveConstants.DRIVE_KINEMATICS.resetHeadings(swerveHeadings);
for (int i = 0; i < swerveModules.length; i++) {
swerveModules[i].stopModule();
}
}
}

/**
* Updates the pose estimator with the pose calculated from the swerve modules.
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/subsystems/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ public void runSetPoint(SwerveModuleState state) {
Logger.recordOutput("Drive/desired turn angle", state.angle.getRotations());
}

public void stopModule() {
io.stopModule();
}
/** Returns the current turn angle of the module. */
public Rotation2d getTurnRotation() {
return inputs.turnAbsolutePosition;
Expand All @@ -77,6 +80,10 @@ public double getTurnVelocity() {
return inputs.turnVelocity;
}

public void xthing(double desiredPositionDegrees) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

dont think u need this

io.xthing(desiredPositionDegrees);
}

/** Returns the current drive position of the module in meters. */
public double getDrivePositionMeters() {
return ModuleConstants.WHEEL_CIRCUMFERENCE_METERS * inputs.drivePosition;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ default void setTurnVoltage(Voltage voltage) {}

default void stopModule() {}

default void xthing(double desiredPositionDegrees) {}
default double getTurnRotations() {
return 0.0;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,11 @@ public double getTurnRotations() {
.getRotations();
}

@Override
public void xthing(double desiredPositionDegrees) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

make a better name

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

actually i dont think this is used in the code so u should just delete it

turnMotor.setControl(mmPositionRequest.withPosition(Degrees.of(desiredPositionDegrees)));
}

@Override
public void stopModule() {
driveMotor.stopMotor();
Expand Down
Loading
Loading