Skip to content

Commit

Permalink
idk
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Oct 28, 2024
1 parent e0149f8 commit 48a3de6
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 47 deletions.
15 changes: 8 additions & 7 deletions src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot.subsystems.swerve;

import static edu.wpi.first.units.Units.*;

import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -86,6 +88,11 @@ public SwerveDrive(
gyroDisconnectedAlert.set(false);
}

/**
* Gets the current velocity of the gyro's yaw
*
* @return the yaw velocity
*/
public double getGyroRate() {
return gyroInputs.yawVelocity;
}
Expand All @@ -110,12 +117,6 @@ public void addPoseEstimatorVisionMeasurement(
poseEstimator.addVisionMeasurement(visionMeasurement, currentTimeStampSeconds);
}

public void setTurnPosition(double position) {
for (SwerveModule module : swerveModules) {
module.setTurnPosition(position);
}
}

/**
* Sets the standard deviations of model states, or how much the april tags contribute to the pose
* estimation of the robot. Lower numbers equal higher confidence and vice versa.
Expand Down Expand Up @@ -145,7 +146,7 @@ public void periodic() {
*/
public void runCharacterization(double volts) {
for (SwerveModule module : swerveModules) {
module.setVoltage(-volts);
module.setVoltage(Volts.of(-volts));
}
}

Expand Down
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/subsystems/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
package frc.robot.subsystems.swerve;

import static edu.wpi.first.units.Units.Volts;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.units.measure.Voltage;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand Down Expand Up @@ -42,9 +45,9 @@ public void periodic() {
updateOdometryPositions();
}

public void setVoltage(double volts) {
public void setVoltage(Voltage volts) {
io.setDriveVoltage(volts);
io.setTurnVoltage(0.0);
io.setTurnVoltage(Volts.zero());
}

public double getDriveVoltage() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.units.measure.Voltage;
import org.littletonrobotics.junction.AutoLog;

public interface ModuleInterface {
Expand Down Expand Up @@ -33,7 +34,11 @@ class ModuleInputs {
public double turnPosition = 0.0;
}

/** Updates the inputs */
/**
* Updates the inputs
*
* @param inputs the inputs to update
*/
void updateInputs(ModuleInputs inputs);

String getCANBus();
Expand Down Expand Up @@ -65,15 +70,9 @@ class ModuleInputs {
*/
void setTurnSpeed(double powerPercent);

/** Enable or disable brake mode on the drive motor. */
void setDriveBrake(boolean enable);

/** Enable or disable brake mode on the turn motor. */
void setTurnBrake(boolean enable);

void setDriveVoltage(double voltage);
void setDriveVoltage(Voltage voltage);

void setTurnVoltage(double voltage);
void setTurnVoltage(Voltage voltage);

void stopModule();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -180,12 +180,12 @@ public double getDriveVelocity() {
}

@Override
public void setDriveVoltage(double volts) {
public void setDriveVoltage(Voltage volts) {
driveMotor.setControl(voltageOut.withOutput(volts));
}

@Override
public void setTurnVoltage(double volts) {
public void setTurnVoltage(Voltage volts) {
turnMotor.setControl(voltageOut.withOutput(volts));
}

Expand Down Expand Up @@ -221,13 +221,9 @@ public void setDesiredState(SwerveModuleState desiredState) {
* ModuleConstants.DRIVE_GEAR_RATIO
/ ModuleConstants.WHEEL_CIRCUMFERENCE_METERS;

driveMotor.setControl(velocityRequest.withVelocity(desiredDriveRPS));
turnMotor.setControl(mmPositionRequest.withPosition(setpoint.angle.getRotations()));
}

@Override
public void setDriveBrake(boolean enable) {
driveMotor.setNeutralMode(enable ? NeutralModeValue.Brake : NeutralModeValue.Coast);
driveMotor.setControl(velocityRequest.withVelocity(RotationsPerSecond.of(desiredDriveRPS)));
turnMotor.setControl(
mmPositionRequest.withPosition(Rotations.of(setpoint.angle.getRotations())));
}

public double getTurnRotations() {
Expand All @@ -236,11 +232,6 @@ public double getTurnRotations() {
.getRotations();
}

@Override
public void setTurnBrake(boolean enable) {
turnMotor.setNeutralMode(enable ? NeutralModeValue.Brake : NeutralModeValue.Coast);
}

@Override
public void stopModule() {
driveMotor.stopMotor();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,13 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.units.measure.Voltage;
import frc.robot.extras.simulation.OdometryTimestampsSim;
import frc.robot.extras.simulation.mechanismSim.swervePhysicsSim.SwerveModuleSimulation;
import frc.robot.subsystems.swerve.SwerveConstants.ModuleConstants;
import java.util.Arrays;

/** Wrapper class around {@link SwerveModuleSimulation} that implements ModuleIO */
/** Wrapper class around {@link SwerveModuleSimulation} */
public class SimulatedModule implements ModuleInterface {
private final SwerveModuleSimulation moduleSimulation;

Expand Down Expand Up @@ -55,7 +56,7 @@ public void updateInputs(ModuleInputs inputs) {
}

@Override
public void setDriveVoltage(double volts) {
public void setDriveVoltage(Voltage volts) {
moduleSimulation.requestDriveVoltageOut(volts);
}

Expand All @@ -78,7 +79,7 @@ public double getTurnAbsolutePosition() {
}

@Override
public void setTurnVoltage(double volts) {
public void setTurnVoltage(Voltage volts) {
moduleSimulation.requestTurnVoltageOut(volts);
}

Expand Down Expand Up @@ -145,18 +146,6 @@ public void setTurnSpeed(double powerPercent) {
throw new UnsupportedOperationException("Unimplemented method 'setTurnSpeed'");
}

@Override
public void setDriveBrake(boolean enable) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'setDriveBrake'");
}

@Override
public void setTurnBrake(boolean enable) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'setTurnBrake'");
}

@Override
public void stopModule() {
// TODO Auto-generated method stub
Expand Down

0 comments on commit 48a3de6

Please sign in to comment.