Skip to content

Commit e52a8b6

Browse files
author
codetoad
committed
built
1 parent d8a542a commit e52a8b6

3 files changed

Lines changed: 88 additions & 88 deletions

File tree

src/main/java/frc/robot/constants/GameConstants.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -21,15 +21,15 @@ public class GameConstants {
2121
public static final double GYRO_DIAGS_ANGLE = 30;
2222

2323
// Debug
24-
public static final boolean SWERVE_DEBUG = true;
25-
public static final boolean INTAKE_DEBUG = true;
26-
public static final boolean CLIMBER_DEBUG = true;
27-
public static final boolean ELEVATOR_DEBUG = true;
28-
public static final boolean CORAL_DEBUG = true;
29-
public static final boolean HIHI_DEBUG = true;
30-
public static final boolean BYEBYE_DEBUG = true;
31-
public static final boolean COMMAND_DEBUG = true;
32-
public static final boolean INPUTS_DEBUG = true;
24+
public static final boolean SWERVE_DEBUG = false;
25+
public static final boolean INTAKE_DEBUG = false;
26+
public static final boolean CLIMBER_DEBUG = false;
27+
public static final boolean ELEVATOR_DEBUG = false;
28+
public static final boolean CORAL_DEBUG = false;
29+
public static final boolean HIHI_DEBUG = false;
30+
public static final boolean BYEBYE_DEBUG = false;
31+
public static final boolean COMMAND_DEBUG = false;
32+
public static final boolean INPUTS_DEBUG = false;
3333
public static final boolean TUNING_MODE = true;
3434

3535
// Speeds

src/main/java/frc/robot/subsystems/swervev3/SwerveDrivetrain.java

Lines changed: 78 additions & 77 deletions
Original file line numberDiff line numberDiff line change
@@ -70,26 +70,26 @@ public SwerveDrivetrain(
7070
this.poseEstimator =
7171
new PoseEstimator(
7272
frontLeft, frontRight, backLeft, backRight, apriltagIO, kinematics, getLastGyro());
73-
if(Constants.TUNING_MODE){
74-
closedLoopTunable =
75-
new LoggedTunableNumber(
76-
"Swerve/currentLimiting/ClosedLoop", Constants.DRIVE_RAMP_RATE_LIMIT);
77-
smartLimitTunable =
78-
new LoggedTunableNumber("Swerve/currentLimiting/SmartLimit", Constants.DRIVE_SMART_LIMIT);
79-
secondaryLimitTunable =
80-
new LoggedTunableNumber(
81-
"Swerve/currentLimiting/SecondaryLimit", Constants.DRIVE_SECONDARY_LIMIT);
82-
drivePTunable = new LoggedTunableNumber("Swerve/drive/P", Constants.DRIVE_PID_P);
83-
driveITunable = new LoggedTunableNumber("Swerve/drive/I", Constants.DRIVE_PID_I);
84-
driveDTunable = new LoggedTunableNumber("Swerve/drive/D", Constants.DRIVE_PID_D);
85-
steerPTunable = new LoggedTunableNumber("Swerve/steer/P", Constants.STEER_PID_P);
86-
steerITunable = new LoggedTunableNumber("Swerve/steer/I", Constants.STEER_PID_I);
87-
steerDTunable = new LoggedTunableNumber("Swerve/steer/D", Constants.STEER_PID_D);
88-
steerMaxAccelerationTunable =
89-
new LoggedTunableNumber("Swerve/steer/maxAccel", Constants.MAX_ANGULAR_SPEED * 150);
90-
steerMaxVelocityTunable =
91-
new LoggedTunableNumber("Swerve/steer/maxVelocity", 2 * Math.PI * 150);
92-
}
73+
if (Constants.TUNING_MODE) {
74+
closedLoopTunable =
75+
new LoggedTunableNumber(
76+
"Swerve/currentLimiting/ClosedLoop", Constants.DRIVE_RAMP_RATE_LIMIT);
77+
smartLimitTunable =
78+
new LoggedTunableNumber("Swerve/currentLimiting/SmartLimit", Constants.DRIVE_SMART_LIMIT);
79+
secondaryLimitTunable =
80+
new LoggedTunableNumber(
81+
"Swerve/currentLimiting/SecondaryLimit", Constants.DRIVE_SECONDARY_LIMIT);
82+
drivePTunable = new LoggedTunableNumber("Swerve/drive/P", Constants.DRIVE_PID_P);
83+
driveITunable = new LoggedTunableNumber("Swerve/drive/I", Constants.DRIVE_PID_I);
84+
driveDTunable = new LoggedTunableNumber("Swerve/drive/D", Constants.DRIVE_PID_D);
85+
steerPTunable = new LoggedTunableNumber("Swerve/steer/P", Constants.STEER_PID_P);
86+
steerITunable = new LoggedTunableNumber("Swerve/steer/I", Constants.STEER_PID_I);
87+
steerDTunable = new LoggedTunableNumber("Swerve/steer/D", Constants.STEER_PID_D);
88+
steerMaxAccelerationTunable =
89+
new LoggedTunableNumber("Swerve/steer/maxAccel", Constants.MAX_ANGULAR_SPEED * 150);
90+
steerMaxVelocityTunable =
91+
new LoggedTunableNumber("Swerve/steer/maxVelocity", 2 * Math.PI * 150);
92+
}
9393
}
9494

9595
@Override
@@ -120,61 +120,63 @@ public void periodic() {
120120
SmartShuffleboard.put("Drive", "BL ABS Pos", backLeft.getAbsPosition());
121121
SmartShuffleboard.put("Drive", "BR ABS Pos", backRight.getAbsPosition());
122122
}
123-
if(Constants.TUNING_MODE){
124-
LoggedTunableNumber.ifChanged(
125-
hashCode(),
126-
() -> {
127-
updateConfig(
128-
closedLoopTunable.get(), secondaryLimitTunable.get(), (int) smartLimitTunable.get());
129-
},
130-
closedLoopTunable,
131-
secondaryLimitTunable,
132-
smartLimitTunable);
133-
LoggedTunableNumber.ifChanged(
134-
hashCode(),
135-
() -> {
136-
frontLeft.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
137-
frontRight.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
138-
backLeft.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
139-
backRight.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
140-
},
141-
drivePTunable,
142-
driveITunable,
143-
driveDTunable);
144-
LoggedTunableNumber.ifChanged(
145-
hashCode(),
146-
() -> {
147-
frontLeft.setSteerPID(
148-
steerPTunable.get(),
149-
steerITunable.get(),
150-
steerDTunable.get(),
151-
steerMaxAccelerationTunable.get(),
152-
steerMaxVelocityTunable.get());
153-
frontRight.setSteerPID(
154-
steerPTunable.get(),
155-
steerITunable.get(),
156-
steerDTunable.get(),
157-
steerMaxAccelerationTunable.get(),
158-
steerMaxVelocityTunable.get());
159-
backLeft.setSteerPID(
160-
steerPTunable.get(),
161-
steerITunable.get(),
162-
steerDTunable.get(),
163-
steerMaxAccelerationTunable.get(),
164-
steerMaxVelocityTunable.get());
165-
backRight.setSteerPID(
166-
steerPTunable.get(),
167-
steerITunable.get(),
168-
steerDTunable.get(),
169-
steerMaxAccelerationTunable.get(),
170-
steerMaxVelocityTunable.get());
171-
},
172-
steerPTunable,
173-
steerITunable,
174-
steerDTunable,
175-
steerMaxAccelerationTunable,
176-
steerMaxVelocityTunable);
177-
}
123+
if (Constants.TUNING_MODE) {
124+
LoggedTunableNumber.ifChanged(
125+
hashCode(),
126+
() -> {
127+
updateConfig(
128+
closedLoopTunable.get(),
129+
secondaryLimitTunable.get(),
130+
(int) smartLimitTunable.get());
131+
},
132+
closedLoopTunable,
133+
secondaryLimitTunable,
134+
smartLimitTunable);
135+
LoggedTunableNumber.ifChanged(
136+
hashCode(),
137+
() -> {
138+
frontLeft.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
139+
frontRight.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
140+
backLeft.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
141+
backRight.setDrivePID(drivePTunable.get(), driveITunable.get(), driveDTunable.get());
142+
},
143+
drivePTunable,
144+
driveITunable,
145+
driveDTunable);
146+
LoggedTunableNumber.ifChanged(
147+
hashCode(),
148+
() -> {
149+
frontLeft.setSteerPID(
150+
steerPTunable.get(),
151+
steerITunable.get(),
152+
steerDTunable.get(),
153+
steerMaxAccelerationTunable.get(),
154+
steerMaxVelocityTunable.get());
155+
frontRight.setSteerPID(
156+
steerPTunable.get(),
157+
steerITunable.get(),
158+
steerDTunable.get(),
159+
steerMaxAccelerationTunable.get(),
160+
steerMaxVelocityTunable.get());
161+
backLeft.setSteerPID(
162+
steerPTunable.get(),
163+
steerITunable.get(),
164+
steerDTunable.get(),
165+
steerMaxAccelerationTunable.get(),
166+
steerMaxVelocityTunable.get());
167+
backRight.setSteerPID(
168+
steerPTunable.get(),
169+
steerITunable.get(),
170+
steerDTunable.get(),
171+
steerMaxAccelerationTunable.get(),
172+
steerMaxVelocityTunable.get());
173+
},
174+
steerPTunable,
175+
steerITunable,
176+
steerDTunable,
177+
steerMaxAccelerationTunable,
178+
steerMaxVelocityTunable);
179+
}
178180
}
179181

180182
private void processInputs() {
@@ -298,8 +300,7 @@ public boolean isFacingTarget() {
298300
* @param secondaryCurrentLimit
299301
* @param smartCurrentLimit
300302
*/
301-
public void updateConfig(
302-
double closedLoopRampRate, double secondaryCurrentLimit, int smartCurrentLimit) {
303+
public void updateConfig(double closedLoopRampRate, double secondaryCurrentLimit, int smartCurrentLimit) {
303304
frontLeft.updateConfig(closedLoopRampRate, secondaryCurrentLimit, smartCurrentLimit);
304305
frontRight.updateConfig(closedLoopRampRate, secondaryCurrentLimit, smartCurrentLimit);
305306
backRight.updateConfig(closedLoopRampRate, secondaryCurrentLimit, smartCurrentLimit);

src/main/java/frc/robot/subsystems/swervev3/io/drive/SwerveDriveMotorIO.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,5 @@ public interface SwerveDriveMotorIO extends LoggableIO<MotorInputs> {
88

99
void resetEncoder();
1010

11-
void updateConfig(
12-
double closedLoopRampRate, double secondaryCurrentLimit, int smartCurrentLimit);
11+
void updateConfig(double closedLoopRampRate, double secondaryCurrentLimit, int smartCurrentLimit);
1312
}

0 commit comments

Comments
 (0)