Skip to content

Commit 4eba78a

Browse files
Bordie at sea comp changes (#188)
1 parent 5fd7839 commit 4eba78a

File tree

10 files changed

+169
-19
lines changed

10 files changed

+169
-19
lines changed

src/main/deploy/pathplanner/autos/OSWRSF_E-D-C.auto

Lines changed: 131 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

src/main/deploy/pathplanner/paths/OSW to D.path

Lines changed: 6 additions & 6 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

src/main/deploy/pathplanner/paths/YSW to K.path

Lines changed: 6 additions & 6 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

src/main/java/frc/robot/Controls.java

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1072,6 +1072,14 @@ private void configureSoloControllerBindings() {
10721072
.asProxy()
10731073
: Commands.none())
10741074
.withName("Manual Coral Intake"));
1075+
// Ground Intake Hold out
1076+
soloController
1077+
.povUp()
1078+
.whileTrue(
1079+
s.groundArm
1080+
.moveToPosition(GroundArm.GROUND_POSITION)
1081+
.andThen(Commands.idle())
1082+
.withName("ground up position"));
10751083
// Arm manual
10761084
soloController
10771085
.rightStick()
@@ -1087,5 +1095,11 @@ private void configureSoloControllerBindings() {
10871095
.startMovingVoltage(
10881096
() -> Volts.of(ElevatorSubsystem.UP_VOLTAGE * -soloController.getLeftY()))
10891097
.withName("Elevator Manual Control"));
1098+
// Ready to score rumble
1099+
Trigger readyToScore = new Trigger(() -> AutoAlign.poseInPlace());
1100+
readyToScore.onTrue(
1101+
Commands.runOnce(() -> soloController.setRumble(RumbleType.kBothRumble, 1.0)));
1102+
readyToScore.onFalse(
1103+
Commands.runOnce(() -> soloController.setRumble(RumbleType.kBothRumble, 0.0)));
10901104
}
10911105
}

src/main/java/frc/robot/Hardware.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ public class Hardware {
4343
public static final int ELEVATOR_ZERO_BUTTON = 0;
4444

4545
// climb DIO
46-
public static final int CLIMB_SENSOR = 9;
46+
public static final int CLIMB_SENSOR = 8;
4747

4848
// vision
4949
public static final String PHOTON_IP = "10.24.12.11";

src/main/java/frc/robot/sensors/ArmSensor.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@ public class ArmSensor {
1717
private final LaserCan mainSensor;
1818
// VALUES ARE IN METERS
1919
private static final double TROUGH_LOWER_LIMIT = 0.10;
20-
private static final double TROUGH_UPPER_LIMIT = 0.20;
20+
private static final double TROUGH_UPPER_LIMIT = 0.25;
2121
private static final double CLAW_LOWER_LIMIT = 0.01;
22-
private static final double CLAW_UPPER_LIMIT = 0.09;
22+
private static final double CLAW_UPPER_LIMIT = 0.13;
2323

2424
public ArmSensor() {
2525
mainSensor = new LaserCan(Hardware.MAIN_ARM_SENSOR);

src/main/java/frc/robot/subsystems/ArmPivot.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232

3333
public class ArmPivot extends SubsystemBase {
3434
// Presets
35-
private final double ARMPIVOT_KP = 50; // previously 38.5
35+
private final double ARMPIVOT_KP = 38.5; // previously 50
3636
private final double ARMPIVOT_KI = 0;
3737
private final double ARMPIVOT_KD = 0;
3838
private final double ARMPIVOT_KS = 0.1;
@@ -195,9 +195,9 @@ public void factoryDefaults() {
195195
talonFXConfiguration.MotorOutput.NeutralMode = NeutralModeValue.Brake;
196196

197197
// enabling current limits
198-
talonFXConfiguration.CurrentLimits.StatorCurrentLimit = 40;
198+
talonFXConfiguration.CurrentLimits.StatorCurrentLimit = 20; // previously 40
199199
talonFXConfiguration.CurrentLimits.StatorCurrentLimitEnable = true;
200-
talonFXConfiguration.CurrentLimits.SupplyCurrentLimit = 20;
200+
talonFXConfiguration.CurrentLimits.SupplyCurrentLimit = 10; // previously 20
201201
talonFXConfiguration.CurrentLimits.SupplyCurrentLimitEnable = true;
202202

203203
// PID

src/main/java/frc/robot/subsystems/ClimbPivot.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ public enum TargetPositions {
4747
private final double CLIMB_OUT_MAX_PRESET = -0.150;
4848
private final double CLIMB_OUT_MIN_PRESET = -0.177;
4949
private final double CLIMBED_MAX_PRESET = -0.325;
50-
private final double CLIMBED_MIN_PRESET = -0.333;
50+
private final double CLIMBED_MIN_PRESET = -0.34;
5151
private final double FORWARD_SOFT_STOP = -0.07;
5252
private final double REVERSE_SOFT_STOP = -78;
5353
private final double CLIMB_OUT_SPEED = 1.0;

src/main/java/frc/robot/subsystems/auto/AutoAlign.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,10 @@ public static boolean readyToScore() {
4848
return isStationary() && isLevel() && isCloseEnough();
4949
}
5050

51+
public static boolean poseInPlace() {
52+
return isStationary() && isCloseEnough();
53+
}
54+
5155
public static boolean isStationary() {
5256
var speeds = AutoLogic.s.drivebaseSubsystem.getState().Speeds;
5357
return MathUtil.isNear(0, speeds.vxMetersPerSecond, 0.01)

src/main/java/frc/robot/subsystems/auto/AutoLogic.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,7 @@ public static enum StartPosition {
123123
new AutoPath("YSMLSF_K-L-A", "YSMLSF_K-L-A"),
124124
new AutoPath("YSWLSC_K-L-A", "YSWLSC_K-L-A"),
125125
new AutoPath("OSWRSF_D-C-B", "OSWRSF_D-C-B"),
126+
new AutoPath("OSWRSF_E-D-C", "OSWRSF_E-D-C"),
126127
new AutoPath("YSMLSC_K-L-A", "YSMLSC_K-L-A"),
127128
new AutoPath("M_H-GHA-IJA", "M_H-GHA-IJA"));
128129

0 commit comments

Comments
 (0)