Skip to content

Commit 716dd02

Browse files
plug
1 parent 6bd149b commit 716dd02

File tree

3 files changed

+19
-9
lines changed

3 files changed

+19
-9
lines changed

src/main/java/frc/robot/Autos.java

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,15 @@ public Autos(
105105
autoChooser.addOption("drive qr", driveSubsystem.driveQuasistaticSysIDCommand(Direction.kReverse));
106106
autoChooser.addOption("drive df", driveSubsystem.driveDynamicSysIDCommand(Direction.kForward));
107107
autoChooser.addOption("drive dr", driveSubsystem.driveDynamicSysIDCommand(Direction.kReverse));
108+
109+
autoChooser.addOption("Shooter qf", shooterSubsystem.sysIdQuasistatic(Direction.kForward));
110+
autoChooser.addOption("Shooter qr", shooterSubsystem.sysIdQuasistatic(Direction.kReverse));
111+
autoChooser.addOption("Shooter df", shooterSubsystem.sysIdDynamic(Direction.kForward));
112+
autoChooser.addOption("Shooter dr", shooterSubsystem.sysIdDynamic(Direction.kReverse));
113+
114+
115+
116+
108117
}
109118

110119
public SendableChooser<Command> getAutoChooser() {

src/main/java/frc/robot/Constants.java

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
import edu.wpi.first.math.geometry.Transform3d;
66
import edu.wpi.first.math.geometry.Translation2d;
77
import edu.wpi.first.math.util.Units;
8+
import edu.wpi.first.units.Unit;
89
import frc.robot.telemetry.tunable.gains.TunableArmElevatorFFGains;
910
import frc.robot.telemetry.tunable.gains.TunableFFGains;
1011
import frc.robot.telemetry.tunable.gains.TunablePIDGains;
@@ -184,20 +185,20 @@ private SwerveConstants() {}
184185
STEER_POSITION_PID_GAINS,
185186
STEER_VELOCITY_FF_GAINS);
186187

187-
public static final SwerveModuleConfiguration FRONT_LEFT_MODULE_CONFIGURATION =
188-
new SwerveModuleConfiguration(
189-
12, 8, 17, true, false, 2.43, true, SHARED_SWERVE_MODULE_CONFIGURATION);
190188
public static final SwerveModuleConfiguration FRONT_RIGHT_MODULE_CONFIGURATION =
191189
new SwerveModuleConfiguration(
192-
13, 5, 18, true, false, 0.34, true, SHARED_SWERVE_MODULE_CONFIGURATION);
193-
194-
public static final SwerveModuleConfiguration BACK_LEFT_MODULE_CONFIGURATION =
190+
12, 8, 17, true, false, 2.462, true, SHARED_SWERVE_MODULE_CONFIGURATION);
191+
public static final SwerveModuleConfiguration FRONT_LEFT_MODULE_CONFIGURATION =
195192
new SwerveModuleConfiguration(
196-
14, 10, 19, true, false, 0.54, true, SHARED_SWERVE_MODULE_CONFIGURATION);
193+
13, 5, 18, false, false, 0.3497+Units.degreesToRadians(180), true, SHARED_SWERVE_MODULE_CONFIGURATION);
197194

198195
public static final SwerveModuleConfiguration BACK_RIGHT_MODULE_CONFIGURATION =
199196
new SwerveModuleConfiguration(
200-
15, 3, 20, true, false, 0.73, true, SHARED_SWERVE_MODULE_CONFIGURATION);
197+
14, 10, 19, true, false, 0.486, true, SHARED_SWERVE_MODULE_CONFIGURATION);
198+
199+
public static final SwerveModuleConfiguration BACK_LEFT_MODULE_CONFIGURATION =
200+
new SwerveModuleConfiguration(
201+
15, 3, 20, true,false, 0.712, true, SHARED_SWERVE_MODULE_CONFIGURATION);
201202
}
202203

203204
public static class AutoConstants {

src/main/java/frc/robot/commands/ScoringCommands.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ public static Command shooterInToleranceCommand(ShooterSubsystem shooterSubsyste
1616

1717
public static Command shootSetpointCloseSpeakerCommand(ShooterSubsystem shooterSubsystem) {
1818
// return shooterSubsystem.runVelocityCommand(Units.rotationsPerMinuteToRadiansPerSecond(10000.0));
19-
return shooterSubsystem.setVoltageCommand(10);
19+
return shooterSubsystem.runVelocityCommand(1000.0);
2020
}
2121

2222

0 commit comments

Comments
 (0)