Skip to content

Commit

Permalink
run format
Browse files Browse the repository at this point in the history
  • Loading branch information
MrTinker64 committed Nov 12, 2024
1 parent 3b215e5 commit d0d79e8
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 28 deletions.
14 changes: 8 additions & 6 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ public class Drive extends SubsystemBase {

Rotation2d rawGyroRotation = new Rotation2d();

public SimpleMotorFeedforward feedforward = new SimpleMotorFeedforward(DriveConstants.kS, DriveConstants.kV, DriveConstants.kA);
public SimpleMotorFeedforward feedforward =
new SimpleMotorFeedforward(DriveConstants.kS, DriveConstants.kV, DriveConstants.kA);

public Drive(DriveIO io, GyroIO gyroIO, PoseManager poseManager) {
this.io = io;
Expand Down Expand Up @@ -113,16 +114,17 @@ public void driveVelocity(double leftMetersPerSec, double rightMetersPerSec) {
double leftRadPerSec = leftMetersPerSec / DriveConstants.WHEEL_RADIUS;
double rightRadPerSec = rightMetersPerSec / DriveConstants.WHEEL_RADIUS;

//TODO:pass in parameters
// setVelocity();
// TODO:pass in parameters
// setVelocity();

}

public void setVelocity(double leftSpeedMetersPerSecond, double rightSpeedMetersPerSecond) {
// Calculate the voltage needed for each side
double leftFeedforward = feedforward.calculate(leftSpeedMetersPerSecond);
double rightFeedforward = feedforward.calculate(rightSpeedMetersPerSecond);

// Set the motor voltages with feedforward applied
io.differentialDrive(leftFeedforward, rightFeedforward);
}
io.differentialDrive(leftFeedforward, rightFeedforward);
}
}
12 changes: 4 additions & 8 deletions src/main/java/frc/robot/subsystems/drive/DriveConstants.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;

public final class DriveConstants {
Expand All @@ -14,11 +13,8 @@ public final class DriveConstants {
public static final DifferentialDriveKinematics kinematics =
new DifferentialDriveKinematics(0.508);


//TODO: Tune THese
public static final double kS = 0;
public static final double kV = 0;
public static final double kA = 0;


// TODO: Tune THese
public static final double kS = 0;
public static final double kV = 0;
public static final double kA = 0;
}
18 changes: 10 additions & 8 deletions src/main/java/frc/robot/subsystems/drive/DriveIO.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
package frc.robot.subsystems.drive;

import org.littletonrobotics.junction.AutoLog;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import org.littletonrobotics.junction.AutoLog;

public interface DriveIO {
@AutoLog
Expand All @@ -17,14 +15,18 @@ public static class DriveIOInputs {
public double rightAppliedVolts = 0.0;
public double leftCurrentAmps = 0.0;
public double rightCurrentAmps = 0.0;

SimpleMotorFeedforward feedforward = new SimpleMotorFeedforward(DriveConstants.kS, DriveConstants.kV, DriveConstants.kA);

SimpleMotorFeedforward feedforward =
new SimpleMotorFeedforward(DriveConstants.kS, DriveConstants.kV, DriveConstants.kA);
}

default void updateInputs(DriveIOInputs inputs) {}

default void arcadeDrive(double xSpeed, double omegaRotation) {}
default void setVelocity(){};
default void differentialDrive(double leftSpeed, double rightSpeed){};


default void setVelocity() {}
;

default void differentialDrive(double leftSpeed, double rightSpeed) {}
;
}
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/subsystems/drive/DriveIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@ public void arcadeDrive(double xSpeed, double omegaRotation) {
driveTrain.arcadeDrive(xSpeed, omegaRotation);
}
}
@Override
public void differentialDrive(double leftSpeed, double rightSpeed){

@Override
public void differentialDrive(double leftSpeed, double rightSpeed) {
driveTrain.tankDrive(leftSpeed, rightSpeed);
}
}
4 changes: 0 additions & 4 deletions src/main/java/frc/robot/subsystems/drive/DriveIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,12 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim.KitbotGearing;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim.KitbotMotor;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim.KitbotWheelSize;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

public class DriveIOSim implements DriveIO {
private DifferentialDrivetrainSim sim =
Expand Down

0 comments on commit d0d79e8

Please sign in to comment.