diff --git a/.DataLogTool/datalogtool.json b/.DataLogTool/datalogtool.json index 70f447c9..3230a842 100644 --- a/.DataLogTool/datalogtool.json +++ b/.DataLogTool/datalogtool.json @@ -1,6 +1,7 @@ { "download": { - "localDir": "C:\\Users\\robotics\\Documents\\Crescendo-2024\\logs", + "deleteAfter": false, + "localDir": "C:\\Users\\admin.CT48-11\\Desktop\\Code\\23-24 Crescendo\\Crescendo-2024\\logs", "serverTeam": "10.11.55.2" } } diff --git a/simgui-ds.json b/simgui-ds.json index c3b41178..21520010 100644 --- a/simgui-ds.json +++ b/simgui-ds.json @@ -4,6 +4,11 @@ "visible": true } }, + "Keyboard 1 Settings": { + "window": { + "visible": true + } + }, "System Joysticks": { "window": { "visible": false diff --git a/src/main/java/org/sciborgs1155/robot/Constants.java b/src/main/java/org/sciborgs1155/robot/Constants.java index 0870ad30..0ef2a18a 100644 --- a/src/main/java/org/sciborgs1155/robot/Constants.java +++ b/src/main/java/org/sciborgs1155/robot/Constants.java @@ -142,7 +142,7 @@ public static Translation2d amp() { } public static Translation2d feedTarget() { - return amp().plus(new Translation2d(Inches.of(0), Inches.of(-24))); + return amp().plus(new Translation2d(Inches.of(0), Inches.of(-100))); } /** Returns whether the provided position is within the boundaries of the field. */ diff --git a/src/main/java/org/sciborgs1155/robot/Robot.java b/src/main/java/org/sciborgs1155/robot/Robot.java index e64d2824..e0a24a07 100644 --- a/src/main/java/org/sciborgs1155/robot/Robot.java +++ b/src/main/java/org/sciborgs1155/robot/Robot.java @@ -232,7 +232,7 @@ private void configureBindings() { // intake (right trigger / top left bump) operator .leftTrigger() - .whileTrue(intake.intake().deadlineWith(feeder.slowForward())) + .whileTrue(intake.intake().deadlineWith(feeder.forward())) .whileTrue(led.rainbow()); // operator feed (left trigger) underfeeding diff --git a/src/main/java/org/sciborgs1155/robot/commands/Shooting.java b/src/main/java/org/sciborgs1155/robot/commands/Shooting.java index bda71d1c..2d63f6c0 100644 --- a/src/main/java/org/sciborgs1155/robot/commands/Shooting.java +++ b/src/main/java/org/sciborgs1155/robot/commands/Shooting.java @@ -54,7 +54,7 @@ public class Shooting implements Logged { * The conversion between shooter tangential velocity and note launch velocity. Perhaps. This may * also account for other errors with our model. */ - public static final DoubleEntry siggysConstant = Tuning.entry("/Robot/Siggy's Constant", 4.42); + public static final DoubleEntry siggysConstant = Tuning.entry("/Robot/Siggy's Constant", 4.15); public static final DoubleEntry ethansConstant = Tuning.entry("/Robot/Ethan's Constant", 3.2); diff --git a/src/main/java/org/sciborgs1155/robot/pivot/PivotConstants.java b/src/main/java/org/sciborgs1155/robot/pivot/PivotConstants.java index 2139b85d..58647488 100644 --- a/src/main/java/org/sciborgs1155/robot/pivot/PivotConstants.java +++ b/src/main/java/org/sciborgs1155/robot/pivot/PivotConstants.java @@ -2,9 +2,12 @@ import static edu.wpi.first.units.Units.*; +import org.sciborgs1155.lib.Tuning; + import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.networktables.DoubleEntry; import edu.wpi.first.units.Angle; import edu.wpi.first.units.Current; import edu.wpi.first.units.Distance; @@ -32,7 +35,7 @@ public class PivotConstants { public static final Measure, Mass>> MOI = (Meters).mult(Meters).mult(Kilograms).of(0.17845); - public static final Measure POSITION_TOLERANCE = Degrees.of(0.8); + public static final Measure POSITION_TOLERANCE = Degrees.of(0.4); public static final Measure MASS = Kilograms.of(1); public static final Measure LENGTH = Inches.of(16); @@ -44,10 +47,11 @@ public class PivotConstants { public static final Measure STARTING_ANGLE = Degrees.of(63.3); public static final Measure MIN_ANGLE = Degrees.of(-45.7); + public static final Measure MAX_ANGLE = STARTING_ANGLE.minus(Degrees.of(1.2)); public static final Measure PRESET_SUBWOOFER_ANGLE = STARTING_ANGLE; - public static final Measure AMP_ANGLE = Radians.of(-0.645); + public static final Measure AMP_ANGLE = Radians.of(-0.59); public static final Measure PRESET_PODIUM_ANGLE = Radians.of(0.5); public static final Measure PRESET_CLIMBING_ANGLE = Radians.of(-0.195); @@ -57,9 +61,9 @@ public class PivotConstants { public static final Measure UNDERFEED_ANGLE = Radians.of(-0.027); public static final Measure OVERFEED_ANGLE = Radians.of(0.619); - public static final double kP = 8.0; + public static final double kP = 12.0; public static final double kI = 0.0; - public static final double kD = 0.5; + public static final double kD = 0.1; public static final double kS = 0.14296; public static final double kV = 1.7305; diff --git a/src/main/java/org/sciborgs1155/robot/shooter/ShooterConstants.java b/src/main/java/org/sciborgs1155/robot/shooter/ShooterConstants.java index c7512441..94629ce9 100644 --- a/src/main/java/org/sciborgs1155/robot/shooter/ShooterConstants.java +++ b/src/main/java/org/sciborgs1155/robot/shooter/ShooterConstants.java @@ -23,7 +23,7 @@ public class ShooterConstants { public static final Measure> VELOCITY_TOLERANCE = RadiansPerSecond.of(5); public static final Measure> IDLE_VELOCITY = RadiansPerSecond.of(300); - public static final Measure> AMP_VELOCITY = RadiansPerSecond.of(150); + public static final Measure> AMP_VELOCITY = RadiansPerSecond.of(90); public static final Measure> DEFAULT_VELOCITY = RadiansPerSecond.of(550); public static final Measure> DEFAULT_NOTE_VELOCITY =