Skip to content

Commit 52110d3

Browse files
committed
changea
1 parent 8467354 commit 52110d3

4 files changed

Lines changed: 80 additions & 84 deletions

File tree

src/main/java/frc/robot/BuildConstants.java

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 339;
9-
public static final String GIT_SHA = "18a691d2f6d19e87115ebcd3031c38f6abed2138";
10-
public static final String GIT_DATE = "2024-08-16 15:05:13 EDT";
8+
public static final int GIT_REVISION = 340;
9+
public static final String GIT_SHA = "8467354a722f04493be8bcf84f7096eb996dcebc";
10+
public static final String GIT_DATE = "2024-08-16 15:09:54 EDT";
1111
public static final String GIT_BRANCH = "marc";
12-
public static final String BUILD_DATE = "2024-08-16 15:06:33 EDT";
13-
public static final long BUILD_UNIX_TIME = 1723835193555L;
12+
public static final String BUILD_DATE = "2024-08-16 15:51:28 EDT";
13+
public static final long BUILD_UNIX_TIME = 1723837888747L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ public boolean isFinished() {
8585
Logger.recordOutput("isFinished align note", shooter.seesNote());
8686
// return false;
8787
return shooter.seesNote() == NoteState.SENSOR
88-
|| shooter.seesNote() == NoteState.CURRENT
89-
|| finished;
88+
|| shooter.seesNote() == NoteState.CURRENT
89+
|| finished;
9090
}
9191
}

src/main/java/frc/robot/subsystems/drive/Drive.java

Lines changed: 72 additions & 76 deletions
Original file line numberDiff line numberDiff line change
@@ -194,15 +194,9 @@ public Drive(
194194
noteLocations.put(NOTE_POSITIONS.C3, FieldConstants.StagingLocations.centerlineTranslations[2]);
195195
noteLocations.put(NOTE_POSITIONS.C2, FieldConstants.StagingLocations.centerlineTranslations[3]);
196196
noteLocations.put(NOTE_POSITIONS.C1, FieldConstants.StagingLocations.centerlineTranslations[4]);
197-
noteLocations.put(
198-
NOTE_POSITIONS.B1,
199-
AllianceFlipUtil.apply(FieldConstants.StagingLocations.spikeTranslations[2]));
200-
noteLocations.put(
201-
NOTE_POSITIONS.B2,
202-
AllianceFlipUtil.apply(FieldConstants.StagingLocations.spikeTranslations[1]));
203-
noteLocations.put(
204-
NOTE_POSITIONS.B3,
205-
AllianceFlipUtil.apply(FieldConstants.StagingLocations.spikeTranslations[0]));
197+
noteLocations.put(NOTE_POSITIONS.B1, FieldConstants.StagingLocations.spikeTranslations[2]);
198+
noteLocations.put(NOTE_POSITIONS.B2, FieldConstants.StagingLocations.spikeTranslations[1]);
199+
noteLocations.put(NOTE_POSITIONS.B3, FieldConstants.StagingLocations.spikeTranslations[0]);
206200
}
207201

208202
public void periodic() {
@@ -731,9 +725,9 @@ public Translation2d getTargetNoteLocation() {
731725
}
732726

733727
Translation2d visionCoords = getCachedNoteLocation();
734-
Translation2d fieldCoords = noteLocations.get(getNote());
728+
Translation2d fieldCoords = AllianceFlipUtil.apply(noteLocations.get(getNote()));
735729
boolean useVisionNoteCoords =
736-
getCachedNoteLocation().getDistance(fieldCoords) < 1.25
730+
getCachedNoteLocation().getDistance(fieldCoords) < 1.323
737731
&& getCachedNoteLocation() != null
738732
&& getCachedNoteTime() != -1
739733
&& noteImageIsNew();
@@ -754,8 +748,7 @@ public PathPlannerPath generateTrajectoryToNote(
754748
double maxAngAccelDegPerSecSquared,
755749
double endVelMetersPerSec) {
756750
Rotation2d targetRotation =
757-
AllianceFlipUtil.apply(
758-
new Rotation2d(target.getX() - getPose().getX(), target.getY() - getPose().getY()));
751+
new Rotation2d(target.getX() - getPose().getX(), target.getY() - getPose().getY());
759752

760753
Logger.recordOutput("Target Note Pose3d", new Pose3d(new Pose2d(target, new Rotation2d())));
761754
List<Translation2d> points =
@@ -772,73 +765,76 @@ public PathPlannerPath generateTrajectoryToNote(
772765
Units.degreesToRadians(maxAngAccelDegPerSecSquared)),
773766
new GoalEndState(endVelMetersPerSec, targetRotation, true));
774767

775-
path.preventFlipping = false;
768+
path.preventFlipping = true;
776769

777770
return path;
778771
}
779772

780-
public PathPlannerPath generatePathToNote() {
781-
Rotation2d targetRotation;
782-
Logger.recordOutput("note timeess", getCachedNoteTime());
783-
if (getCachedNoteTime() != -1) {
784-
// led.setState(LED_STATE.FLASHING_RED);
785-
Translation2d cachedNoteT2d = getCachedNoteLocation();
786-
Logger.recordOutput("better translate", cachedNoteT2d);
787-
if (noteImageIsNew()) {
788-
789-
targetRotation =
790-
new Rotation2d(
791-
cachedNoteT2d.getX() - getPose().getX(), cachedNoteT2d.getY() - getPose().getY());
792-
List<Translation2d> pointsToNote;
793-
if (DriverStation.getAlliance().get().equals(Alliance.Blue)) {
794-
Logger.recordOutput(
795-
"goal point blue",
796-
new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
797-
pointsToNote =
798-
PathPlannerPath.bezierFromPoses(
799-
new Pose2d(getPose().getX(), getPose().getY(), targetRotation),
800-
new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
801-
} else {
802-
Logger.recordOutput(
803-
"goal point red",
804-
new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
805-
pointsToNote =
806-
PathPlannerPath.bezierFromPoses(
807-
new Pose2d(getPose().getX(), getPose().getY(), targetRotation),
808-
new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
809-
}
810-
PathPlannerPath path =
811-
new PathPlannerPath(
812-
pointsToNote,
813-
new PathConstraints(
814-
3, 2.45, Units.degreesToRadians(100), Units.degreesToRadians(180)),
815-
new GoalEndState(0.5, targetRotation, true));
816-
817-
path.preventFlipping = true;
818-
// AutoBuilder.followPath(path).schedule();
819-
Logger.recordOutput("follow path", true);
820-
return path;
821-
} else {
822-
// return;
823-
// led.setState(LED_STATE.PAPAYA_ORANGE);
824-
return new PathPlannerPath(
825-
PathPlannerPath.bezierFromPoses(
826-
new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation()),
827-
new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation())),
828-
new PathConstraints(0.1, 1.5, Units.degreesToRadians(100), Units.degreesToRadians(180)),
829-
new GoalEndState(0.5, getPose().getRotation(), true));
830-
}
831-
} else {
832-
// return;
833-
// led.setState(LED_STATE.WILLIAMS_BLUE);
834-
return new PathPlannerPath(
835-
PathPlannerPath.bezierFromPoses(
836-
new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation()),
837-
new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation())),
838-
new PathConstraints(0.1, 1.5, Units.degreesToRadians(100), Units.degreesToRadians(180)),
839-
new GoalEndState(0.5, getPose().getRotation(), true));
840-
}
841-
}
773+
// public PathPlannerPath generatePathToNote() {
774+
// Rotation2d targetRotation;
775+
// Logger.recordOutput("note timeess", getCachedNoteTime());
776+
// if (getCachedNoteTime() != -1) {
777+
// // led.setState(LED_STATE.FLASHING_RED);
778+
// Translation2d cachedNoteT2d = getCachedNoteLocation();
779+
// Logger.recordOutput("better translate", cachedNoteT2d);
780+
// if (noteImageIsNew()) {
781+
782+
// targetRotation =
783+
// new Rotation2d(
784+
// cachedNoteT2d.getX() - getPose().getX(), cachedNoteT2d.getY() -
785+
// getPose().getY());
786+
// List<Translation2d> pointsToNote;
787+
// if (DriverStation.getAlliance().get().equals(Alliance.Blue)) {
788+
// Logger.recordOutput(
789+
// "goal point blue",
790+
// new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
791+
// pointsToNote =
792+
// PathPlannerPath.bezierFromPoses(
793+
// new Pose2d(getPose().getX(), getPose().getY(), targetRotation),
794+
// new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
795+
// } else {
796+
// Logger.recordOutput(
797+
// "goal point red",
798+
// new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
799+
// pointsToNote =
800+
// PathPlannerPath.bezierFromPoses(
801+
// new Pose2d(getPose().getX(), getPose().getY(), targetRotation),
802+
// new Pose2d(cachedNoteT2d.getX(), cachedNoteT2d.getY(), targetRotation));
803+
// }
804+
// PathPlannerPath path =
805+
// new PathPlannerPath(
806+
// pointsToNote,
807+
// new PathConstraints(
808+
// 3, 2.45, Units.degreesToRadians(100), Units.degreesToRadians(180)),
809+
// new GoalEndState(0.5, targetRotation, true));
810+
811+
// path.preventFlipping = true;
812+
// // AutoBuilder.followPath(path).schedule();
813+
// Logger.recordOutput("follow path", true);
814+
// return path;
815+
// } else {
816+
// // return;
817+
// // led.setState(LED_STATE.PAPAYA_ORANGE);
818+
// return new PathPlannerPath(
819+
// PathPlannerPath.bezierFromPoses(
820+
// new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation()),
821+
// new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation())),
822+
// new PathConstraints(0.1, 1.5, Units.degreesToRadians(100),
823+
// Units.degreesToRadians(180)),
824+
// new GoalEndState(0.5, getPose().getRotation(), true));
825+
// }
826+
// } else {
827+
// // return;
828+
// // led.setState(LED_STATE.WILLIAMS_BLUE);
829+
// return new PathPlannerPath(
830+
// PathPlannerPath.bezierFromPoses(
831+
// new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation()),
832+
// new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation())),
833+
// new PathConstraints(0.1, 1.5, Units.degreesToRadians(100),
834+
// Units.degreesToRadians(180)),
835+
// new GoalEndState(0.5, getPose().getRotation(), true));
836+
// }
837+
// }
842838

843839
public Command createPathFindingCommand(Pose2d target) {
844840
Pose2d coord = target;

src/main/java/frc/robot/util/FieldConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ public static final class StagingLocations {
4949
static {
5050
for (int i = 0; i < centerlineTranslations.length; i++) {
5151
centerlineTranslations[i] =
52-
new Translation2d(centerlineX, centerlineFirstY + (i * centerlineSeparationY));
52+
new Translation2d(centerlineX + 0.25, centerlineFirstY + (i * centerlineSeparationY));
5353
}
5454
}
5555

0 commit comments

Comments
 (0)