Skip to content

Commit

Permalink
Remove redundant constants, convert SmartNumbers to double
Browse files Browse the repository at this point in the history
  • Loading branch information
BenG49 committed Jan 26, 2024
1 parent 26ac943 commit ae6197f
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 24 deletions.
30 changes: 14 additions & 16 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,31 +50,29 @@ public interface Swerve {
double LENGTH = Units.inchesToMeters(26);

SmartNumber MODULE_VELOCITY_DEADBAND = new SmartNumber("Swerve/Module velocity deadband (m per s)", 0.02);
SmartNumber MAX_MODULE_SPEED = new SmartNumber("Swerve/Maximum module speed (m per s)", 5.06);
SmartNumber MAX_MODULE_TURN = new SmartNumber("Swerve/Maximum module turn (rad per s)", 6.28);
double MAX_MODULE_SPEED = 5.88;

public interface Turn {
SmartNumber kP = new SmartNumber("Swerve/Turn/kP", 6.0);
SmartNumber kI = new SmartNumber("Swerve/Turn/kI", 0.0);
SmartNumber kD = new SmartNumber("Swerve/Turn/kD", 0.15);
double kP = 6.0;
double kI = 0.0;
double kD = 0.15;

SmartNumber kS = new SmartNumber("Swerve/Turn/kS", 0.44076);
SmartNumber kV = new SmartNumber("Swerve/Turn/kV", 0.0056191);
SmartNumber kA = new SmartNumber("Swerve/Turn/kA", 0.00042985);
double kS = 0.44076;
double kV = 0.0056191;
double kA = 0.00042985;
}

public interface Drive {
SmartNumber kP = new SmartNumber("Swerve/Drive/kP", 0.00019162);
SmartNumber kI = new SmartNumber("Swerve/Drive/kI", 0.0);
SmartNumber kD = new SmartNumber("Swerve/Drive/kD", 0.0);
double kP = 0.00019162;
double kI = 0.0;
double kD = 0.0;

SmartNumber kS = new SmartNumber("Swerve/Drive/kS", 0.36493);
SmartNumber kV = new SmartNumber("Swerve/Drive/kV", 2.448);
SmartNumber kA = new SmartNumber("Swerve/Drive/kA", 0.16408);
double kS = 0.36493;
double kV = 2.448;
double kA = 0.16408;
}

public interface Motion {

PIDConstants XY = new PIDConstants(0.7, 0, 0.02);
PIDConstants THETA = new PIDConstants(10, 0, 0.1);
}
Expand Down Expand Up @@ -122,7 +120,7 @@ public interface Drive {
SmartNumber RC = new SmartNumber("Driver Settings/Drive/RC", 0.01);
SmartNumber POWER = new SmartNumber("Driver Settings/Drive/Power", 2);

SmartNumber MAX_TELEOP_SPEED = new SmartNumber("Driver Settings/Drive/Max Speed", Swerve.MAX_MODULE_SPEED.get());
SmartNumber MAX_TELEOP_SPEED = new SmartNumber("Driver Settings/Drive/Max Speed", Swerve.MAX_MODULE_SPEED);
SmartNumber MAX_TELEOP_ACCEL = new SmartNumber("Driver Settings/Drive/Max Accleration", 15);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import com.kauailabs.navx.frc.AHRS;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.PathPlannerLogging;
import com.pathplanner.lib.util.ReplanningConfig;
import com.stuypulse.robot.Robot;
Expand All @@ -16,7 +15,6 @@
import com.stuypulse.robot.constants.Settings.Swerve.FrontLeft;
import com.stuypulse.robot.constants.Settings.Swerve.FrontRight;
import com.stuypulse.robot.subsystems.odometry.AbstractOdometry;
import com.stuypulse.robot.subsystems.odometry.Odometry;
import com.stuypulse.robot.subsystems.swerve.module.SimModule;
import com.stuypulse.robot.subsystems.swerve.module.AbstractModule;
import com.stuypulse.robot.subsystems.swerve.module.JimModule;
Expand Down Expand Up @@ -91,7 +89,7 @@ public void configureAutoBuilder() {
new HolonomicPathFollowerConfig(
Swerve.Motion.XY,
Swerve.Motion.THETA,
Swerve.MAX_MODULE_SPEED.get(),
Swerve.MAX_MODULE_SPEED,
Math.hypot(Swerve.LENGTH, Swerve.WIDTH),
new ReplanningConfig(true, true)),
() -> {
Expand Down Expand Up @@ -172,7 +170,7 @@ public void setModuleStates(SwerveModuleState... states) {
);
}

SwerveDriveKinematics.desaturateWheelSpeeds(states, Swerve.MAX_MODULE_SPEED.get());
SwerveDriveKinematics.desaturateWheelSpeeds(states, Swerve.MAX_MODULE_SPEED);

for (int i = 0; i < modules.length; i++) {
modules[i].setTargetState(filterModuleState(states[i]));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import com.stuypulse.robot.Robot;
import com.stuypulse.robot.Robot.MatchState;
import com.stuypulse.robot.constants.Motors;
import com.stuypulse.robot.constants.Settings.Driver;
import com.stuypulse.robot.constants.Settings.Swerve;
import com.stuypulse.robot.constants.Settings.Swerve.Drive;
import com.stuypulse.robot.constants.Settings.Swerve.Encoder;
Expand Down Expand Up @@ -70,7 +71,7 @@ public RetepModule(String id, Translation2d translationOffset, Rotation2d angleO
.add(new MotorFeedforward(Drive.kS, Drive.kV, Drive.kA).velocity());

turnController = new AnglePIDController(Turn.kP, Turn.kI, Turn.kD)
.setSetpointFilter(new ARateLimit(Swerve.MAX_MODULE_TURN))
.setSetpointFilter(new ARateLimit(Driver.Turn.MAX_TELEOP_TURNING))
.setOutputFilter(x -> -x);

targetState = new SwerveModuleState();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.stuypulse.robot.Robot;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Driver;
import com.stuypulse.robot.constants.Settings.Swerve;
import com.stuypulse.robot.constants.Settings.Swerve.Drive;
import com.stuypulse.robot.constants.Settings.Swerve.Turn;
Expand Down Expand Up @@ -65,10 +66,10 @@ public SimModule(String id, Translation2d translationOffset) {
.add(new MotorFeedforward(Drive.kS, Drive.kV, Drive.kA).velocity());

turnController = new AnglePIDController(Turn.kP, Turn.kI, Turn.kD)
.setSetpointFilter(new ARateLimit(Swerve.MAX_MODULE_TURN));
.setSetpointFilter(new ARateLimit(Driver.Turn.MAX_TELEOP_TURNING));

driveSim = new LinearSystemSim<>(identifyVelocityPositionSystem(Drive.kV.get(), Drive.kA.get()));
turnSim = new LinearSystemSim<N2, N1, N1>(LinearSystemId.identifyPositionSystem(Turn.kV.get(), Turn.kA.get()));
driveSim = new LinearSystemSim<>(identifyVelocityPositionSystem(Drive.kV, Drive.kA));
turnSim = new LinearSystemSim<N2, N1, N1>(LinearSystemId.identifyPositionSystem(Turn.kV, Turn.kA));

targetState = new SwerveModuleState();
}
Expand Down

0 comments on commit ae6197f

Please sign in to comment.