From 68568021dbe29ea2b2ac0849d9a4a39e5526558b Mon Sep 17 00:00:00 2001 From: Ivan Chen Date: Sat, 27 Jan 2024 09:04:45 -0500 Subject: [PATCH] Update ports + recalibrate modules + remove redundant rate limits --- src/main/java/com/stuypulse/robot/RobotContainer.java | 6 +++--- .../java/com/stuypulse/robot/constants/Cameras.java | 2 +- src/main/java/com/stuypulse/robot/constants/Ports.java | 8 ++++---- .../java/com/stuypulse/robot/constants/Settings.java | 10 +++++----- 4 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/main/java/com/stuypulse/robot/RobotContainer.java b/src/main/java/com/stuypulse/robot/RobotContainer.java index caf7cb2..ff70618 100644 --- a/src/main/java/com/stuypulse/robot/RobotContainer.java +++ b/src/main/java/com/stuypulse/robot/RobotContainer.java @@ -93,14 +93,14 @@ private void configureButtonBindings() { .onFalse(new IntakeDeacquire()) .onFalse(new IntakeStop()); - // driver.getLeftButton().whileTrue(new SwerveDriveToPose(new Pose2d(4, 5.5, new Rotation2d()))); + driver.getBottomButton().whileTrue(new SwerveDriveToPose(new Pose2d(2, 5.5, new Rotation2d(Units.degreesToRadians(180))))); // driver.getRightButton().whileTrue(new SwerveDriveToPose(new Pose2d(1.5, 5.5, new Rotation2d()))); - // driver.getTopButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(7).getPose().toPose2d(), driver)); + driver.getTopButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(7).getPose().toPose2d(), driver)); // driver.getBottomButton().whileTrue(new SwerveDriveWithAiming(Field.getFiducial(8).getPose().toPose2d(), driver)); driver.getLeftButton().whileTrue(new SwerveDriveToScore()); driver.getRightButton().whileTrue(new SwerveDriveDriveToScore(driver)); - driver.getBottomButton().whileTrue(AutoBuilder.pathfindToPose(new Pose2d(), new PathConstraints(3, 4, Units.degreesToRadians(540), Units.degreesToRadians(720)), 0, 0)); + // driver.getBottomButton().whileTrue(AutoBuilder.pathfindToPose(new Pose2d(), new PathConstraints(3, 4, Units.degreesToRadians(540), Units.degreesToRadians(720)), 0, 0)); } /**************/ diff --git a/src/main/java/com/stuypulse/robot/constants/Cameras.java b/src/main/java/com/stuypulse/robot/constants/Cameras.java index 452c83f..81860b2 100644 --- a/src/main/java/com/stuypulse/robot/constants/Cameras.java +++ b/src/main/java/com/stuypulse/robot/constants/Cameras.java @@ -14,7 +14,7 @@ public interface Cameras { - public static final CameraConfig DEFAULT_CAMERA = new CameraConfig("default", + public static final CameraConfig DEFAULT_CAMERA = new CameraConfig("samera1", new Pose3d(-Units.inchesToMeters(12), -Units.inchesToMeters(0), +Units.inchesToMeters(5), diff --git a/src/main/java/com/stuypulse/robot/constants/Ports.java b/src/main/java/com/stuypulse/robot/constants/Ports.java index 4647e2d..6894a1f 100644 --- a/src/main/java/com/stuypulse/robot/constants/Ports.java +++ b/src/main/java/com/stuypulse/robot/constants/Ports.java @@ -17,16 +17,16 @@ public interface Swerve { public interface BackLeft { int DRIVE = 10; int TURN = 11; - int ENCODER = 2; + int ENCODER = 3; } - public interface BackRight { + public interface BackRight { int DRIVE = 12; int TURN = 13; int ENCODER = 1; } - public interface FrontRight { + public interface FrontRight { int DRIVE = 14; int TURN = 15; int ENCODER = 4; @@ -35,7 +35,7 @@ public interface FrontRight { public interface FrontLeft { int DRIVE = 16; int TURN = 17; - int ENCODER = 3; + int ENCODER = 2; } } diff --git a/src/main/java/com/stuypulse/robot/constants/Settings.java b/src/main/java/com/stuypulse/robot/constants/Settings.java index 2eaecc7..cbbb2dc 100644 --- a/src/main/java/com/stuypulse/robot/constants/Settings.java +++ b/src/main/java/com/stuypulse/robot/constants/Settings.java @@ -79,25 +79,25 @@ public interface Motion { public interface FrontRight { String ID = "Front Right"; - Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(208.212891 + 180); + Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-153.632812 + 180); Translation2d MODULE_OFFSET = new Translation2d(WIDTH * +0.5, LENGTH * -0.5); } public interface FrontLeft { String ID = "Front Left"; - Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(154.511719 + 180); + Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(147.919922 + 180); Translation2d MODULE_OFFSET = new Translation2d(WIDTH * +0.5, LENGTH * +0.5); } public interface BackLeft { String ID = "Back Left"; - Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(65.566406 + 180); + Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(73.125 + 180); Translation2d MODULE_OFFSET = new Translation2d(WIDTH * -0.5, LENGTH * +0.5); } public interface BackRight { String ID = "Back Right"; - Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(47.197266 + 180); + Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(-2.02184 + 180); Translation2d MODULE_OFFSET = new Translation2d(WIDTH * -0.5, LENGTH * -0.5); } @@ -130,7 +130,7 @@ public interface Turn { SmartNumber RC = new SmartNumber("Driver Settings/Turn/RC", 0.1); SmartNumber POWER = new SmartNumber("Driver Settings/Turn/Power", 2); - SmartNumber MAX_TELEOP_TURNING = new SmartNumber("Driver Settings/Turn/Max Turning", 6.0); + SmartNumber MAX_TELEOP_TURNING = new SmartNumber("Driver Settings/Turn/Max Turning", 6.28); public interface GyroFeedback { SmartBoolean GYRO_FEEDBACK_ENABLED = new SmartBoolean("Driver Settings/Gyro Feedback/Enabled", true);