Skip to content

Commit 6a7e477

Browse files
committed
Merge branch 'post-wne' into auto-adjustments
2 parents 5b82050 + e426a56 commit 6a7e477

6 files changed

Lines changed: 277 additions & 95 deletions

File tree

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

Lines changed: 27 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -107,17 +107,27 @@ public static class SwerveConstants { // all swerve on CAN ID range 1-9
107107

108108
public static final ControlConstants kPresetRotControlConstants = new ControlConstants(
109109
"SwervePresetRot",
110-
10,
110+
7,
111111
0,
112-
1,
112+
0.1,
113+
0,
114+
0,
115+
0
116+
);
117+
118+
public static final ControlConstants kPresetPosXControlConstants = new ControlConstants(
119+
"SwervePresetPos",
120+
10, // TODO probably turn up
121+
0,
122+
0.2,
113123
0,
114124
0,
115125
0
116126
);
117127

118-
public static final ControlConstants kPresetPosControlConstants = new ControlConstants(
128+
public static final ControlConstants kPresetPosYControlConstants = new ControlConstants(
119129
"SwervePresetPos",
120-
2.5, // TODO probably turn up
130+
10, // TODO probably turn up
121131
0,
122132
0,
123133
0,
@@ -231,6 +241,7 @@ public static class ElevatorConstants { // CAN ID range 11-19
231241
public static final SparkMaxConfig elevatorLeaderConfig = new SparkMaxConfig();
232242
public static final SparkMaxConfig elevatorFollowerConfig = new SparkMaxConfig();
233243
public static final SparkMaxConfig effectorConfig = new SparkMaxConfig(); // also used for funnel motor, since is the same
244+
public static final SparkMaxConfig dealgaeConfig = new SparkMaxConfig();
234245

235246
static {
236247
elevatorLeaderConfig
@@ -277,6 +288,15 @@ public static class ElevatorConstants { // CAN ID range 11-19
277288
.positionConversionFactor(1) // revolutions
278289
.velocityConversionFactor(1) // RPM
279290
;
291+
292+
dealgaeConfig
293+
.idleMode(IdleMode.kCoast)
294+
.smartCurrentLimit(30)
295+
.voltageCompensation(12)
296+
; dealgaeConfig.encoder
297+
.positionConversionFactor(1) // revolutions
298+
.velocityConversionFactor(1) // RPM
299+
;
280300
}
281301
}
282302

@@ -381,8 +401,9 @@ public static class FieldConstants {
381401
public static final Translation2d fieldCenter = new Translation2d(fieldWidth / 2, fieldHeight / 2);
382402
public static final Transform2d betweenReefsTransform = new Transform2d(reefCenterRed.minus(reefCenterBlue), Rotation2d.kZero);
383403

384-
public static final Pose2d blueCloseLeftReef = new Pose2d(3.2512, fieldHeight / 2 + 0.164338, Rotation2d.kZero);
385-
public static final Pose2d blueCloseRightReef = new Pose2d(3.2512, fieldHeight / 2 - 0.164338, Rotation2d.kZero);
404+
public static final double xOffsetIntoReef = 0.04;
405+
public static final Pose2d blueCloseLeftReef = new Pose2d(3.2512 + xOffsetIntoReef, fieldHeight / 2 + 0.164338, Rotation2d.kZero);
406+
public static final Pose2d blueCloseRightReef = new Pose2d(3.2512 + xOffsetIntoReef, fieldHeight / 2 - 0.164338, Rotation2d.kZero);
386407
public static final Pose2d redFarLeftReef = blueCloseLeftReef.plus(betweenReefsTransform);
387408
public static final Pose2d redFarRightReef = blueCloseRightReef.plus(betweenReefsTransform);
388409

src/main/java/frc/robot/RobotContainer.java

Lines changed: 24 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -100,14 +100,14 @@ private void configureBindings() {
100100
);
101101
overrideElevatorFactorCombo.getTrigger().onTrue(Commands.runOnce(() -> {}));
102102
Shuffleboard.getTab("Teleoperated")
103-
.addBoolean("EleFact Override", overrideElevatorFactorCombo.getTrigger()).
104-
withPosition(8, 0)
103+
.addBoolean("EleFact Override", overrideElevatorFactorCombo.getTrigger())
104+
.withPosition(8, 2)
105105
.withSize(1, 1);
106106

107107
swerve.setToAimSuppliers(
108-
driverController.leftTrigger()::getAsBoolean, // aim reef
109-
driverController.b()::getAsBoolean, // aim processor
110-
driverController.a()::getAsBoolean // aim station
108+
driverController.leftTrigger(), // aim reef
109+
driverController.b(), // aim processor
110+
driverController.a() // aim station
111111
);
112112
swerve.setReefChooserSuppliers(
113113
driverController::getRightX,
@@ -119,17 +119,26 @@ private void configureBindings() {
119119
driverController::getLeftY, // vy
120120
driverController::getRightX, // omega
121121
driverController::getRightTriggerAxis, // raw slow input
122-
driverController.leftBumper()::getAsBoolean, // robot centric
123-
driverController.rightBumper()::getAsBoolean // no optimize
122+
driverController.rightBumper(), // robot centric
123+
driverController.start() // no optimize
124124
));
125125

126126
driverController.y().onTrue(swerve.runZeroGyro());
127127
driverController.back().onTrue(swerve.runToggleToXPosition(true));
128128
driverController.b().onTrue(swerve.runUpdateControlConstants().andThen(elevator.runUpdateControlConstants()));
129-
driverController.start().onTrue(swerve.runSetTempPose());
130129
driverController.povLeft().onTrue(swerve.runTogglePresetPosition(PresetPositionType.LEFTREEF));
131130
driverController.povRight().onTrue(swerve.runTogglePresetPosition(PresetPositionType.RIGHTREEF));
132131
driverController.povUp().onTrue(swerve.runTogglePresetPosition(PresetPositionType.PROCESSOR));
132+
driverController.leftBumper().onTrue(swerve.runSetPresetXEnabled(true));
133+
driverController.leftBumper().onFalse(swerve.runSetPresetXEnabled(false));
134+
135+
Combo setTempPoseCombo = new Combo("setTempPose Combo", 0.5,
136+
driverController.rightBumper(),
137+
driverController.rightBumper().negate(),
138+
driverController.rightBumper(),
139+
driverController.start()
140+
);
141+
setTempPoseCombo.getTrigger().onTrue(swerve.runSetTempPose());
133142

134143
// if(Constants.simMode.equals(RobotMode.SIM)) {
135144
// swerve.setDefaultCommand(swerve.runSimOdometryMoveBy(
@@ -146,7 +155,7 @@ private void configureBindings() {
146155

147156
// driverController.povUp().onTrue(elevator.runEffectorPreferences());
148157
// driverController.povUp().onFalse(elevator.runEffector(0, 0));
149-
// driverController.povDown().onTrue(elevator.runaEffectorPreferences());
158+
// driverController.povDown().onTrue(elevator.runReversedEffectorPreferences());
150159
// driverController.povDown().onFalse(elevator.runEffector(0, 0));
151160

152161
// driverController.povLeft().onTrue(elevator.runElevatorOpenLoopPreferences());
@@ -164,16 +173,18 @@ private void configureBindings() {
164173
.addBoolean("Aligned Override", alignedOverrideCombo.getTrigger()).
165174
withPosition(3, 2)
166175
.withSize(1, 1);
176+
elevator.setIsAlignedSupplier(() -> swerve.isAligned() || alignedOverrideCombo.getTrigger().getAsBoolean());
177+
elevator.setScoreComboSupplier(auxController.rightTrigger());
178+
elevator.setErrorDistanceSupplier(swerve::getErrorDistance);
167179

168180
auxController.b().onTrue(elevator.runToElevatorPosition(ElevatorPosition.HOME));
169181
auxController.a().onTrue(elevator.runToElevatorPosition(ElevatorPosition.L1));
170182
auxController.x().onTrue(elevator.runToElevatorPosition(ElevatorPosition.L2));
171183
auxController.y().onTrue(elevator.runToElevatorPosition(ElevatorPosition.L3));
172184
auxController.leftBumper().onTrue(elevator.runIntakeEffector(
173-
5, // effector volts
174-
-2, // funnel volts
175-
() -> swerve.isAligned() || alignedOverrideCombo.getTrigger().getAsBoolean() // is aligned supplier
176-
// () -> true
185+
// TODO slow to 4
186+
4, // effector volts
187+
-2 // funnel volts
177188
));
178189
auxController.leftBumper().onFalse(elevator.runStopIntakeEffector());
179190

0 commit comments

Comments
 (0)