Skip to content

Commit 0a0ebc9

Browse files
committed
coord swaps rotation flip
1 parent b2176b8 commit 0a0ebc9

6 files changed

Lines changed: 50 additions & 91 deletions

File tree

src/main/deploy/pathplanner/paths/New New New New New Path.path

Lines changed: 26 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -3,25 +3,41 @@
33
"waypoints": [
44
{
55
"anchor": {
6-
"x": 2.0,
7-
"y": 7.0
6+
"x": 1.8292964403332503,
7+
"y": 8.092188053135022
88
},
99
"prevControl": null,
1010
"nextControl": {
11-
"x": 3.0,
12-
"y": 7.0
11+
"x": 1.8477029345453428,
12+
"y": 8.11979779445316
1313
},
1414
"isLocked": false,
1515
"linkedName": null
1616
},
1717
{
1818
"anchor": {
19-
"x": 8.317099886696207,
20-
"y": 7.424670370025476
19+
"x": 1.4598536820392034,
20+
"y": 0.8466987337562125
2121
},
2222
"prevControl": {
23-
"x": 7.317099886696207,
24-
"y": 7.424670370025476
23+
"x": 0.4598536820392034,
24+
"y": 0.8466987337562125
25+
},
26+
"nextControl": {
27+
"x": 2.4598536820392036,
28+
"y": 0.8466987337562125
29+
},
30+
"isLocked": false,
31+
"linkedName": null
32+
},
33+
{
34+
"anchor": {
35+
"x": 15.108269140305099,
36+
"y": 4.086241715084328
37+
},
38+
"prevControl": {
39+
"x": 9.041752330141433,
40+
"y": 2.112145210837508
2541
},
2642
"nextControl": null,
2743
"isLocked": false,
@@ -39,13 +55,13 @@
3955
},
4056
"goalEndState": {
4157
"velocity": 0,
42-
"rotation": 5.909363189683607,
58+
"rotation": -133.60281897270377,
4359
"rotateFast": false
4460
},
4561
"reversed": false,
4662
"folder": null,
4763
"previewStartingState": {
48-
"rotation": 89.3309723976918,
64+
"rotation": 43.31531568210366,
4965
"velocity": 0
5066
},
5167
"useDefaultConstraints": true

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

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,14 +3,14 @@
33
/** Automatically generated file containing build version information. */
44
public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
6-
public static final String MAVEN_NAME = "2024 Robot Code";
6+
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 317;
9-
public static final String GIT_SHA = "b87e886bb4404f32a660af7d73877f5015d1e1f5";
10-
public static final String GIT_DATE = "2024-08-14 00:51:38 EDT";
8+
public static final int GIT_REVISION = 318;
9+
public static final String GIT_SHA = "b2176b8c5ef241eedb55dea925bbab869219b7ca";
10+
public static final String GIT_DATE = "2024-08-14 20:36:51 EDT";
1111
public static final String GIT_BRANCH = "note-filtering";
12-
public static final String BUILD_DATE = "2024-08-14 20:34:11 EDT";
13-
public static final long BUILD_UNIX_TIME = 1723682051564L;
12+
public static final String BUILD_DATE = "2024-08-14 21:54:44 EDT";
13+
public static final long BUILD_UNIX_TIME = 1723686884925L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}

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

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ public void initialize() {
7777
pivot.setPivotGoal(Constants.PivotConstants.INTAKE_SETPOINT_DEG);
7878
targetNoteLocation = noteLocations.get(drive.getTargetNote());
7979
useGeneratedPathCommand =
80-
drive.getCachedNoteLocation().getDistance(targetNoteLocation) < 2.5
80+
drive.getCachedNoteLocation().getDistance(targetNoteLocation) < 1.25
8181
&& drive.getCachedNoteLocation() != null;
8282
Logger.recordOutput(
8383
"cached note distance ", drive.getCachedNoteLocation().getDistance(targetNoteLocation));
@@ -89,17 +89,11 @@ public void initialize() {
8989

9090
generatedPathCommand.initialize();
9191
} else {
92-
// targetNoteRotation =
93-
// new Rotation2d(
94-
// targetNoteLocation.getX() - drive.getPose().getX(),
95-
// targetNoteLocation.getY() - drive.getPose().getY());
96-
// targetNotePathCommand =
97-
// drive.generateTrajectory(
98-
// new Pose2d(targetNoteLocation, targetNoteRotation), 3, 2.45, 100, 180, 0.5);
99-
targetNotePathCommand =
100-
AutoBuilder.followPath(drive.generatePathToNoteBlind(targetNoteLocation));
101-
102-
targetNotePathCommand.initialize();
92+
targetNotePathCommand =
93+
AutoBuilder.followPath(
94+
drive.generateTrajectory(targetNoteLocation, 3, 2.45, 100, 180, 0.5));
95+
96+
targetNotePathCommand.initialize();
10397
}
10498
}
10599

@@ -111,7 +105,7 @@ public void execute() {
111105
if (useGeneratedPathCommand) {
112106
generatedPathCommand.execute();
113107
} else {
114-
targetNotePathCommand.execute();
108+
targetNotePathCommand.execute();
115109
}
116110

117111
Logger.recordOutput("path is finished", finished);

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

Lines changed: 0 additions & 54 deletions
This file was deleted.

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

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@
5353
import frc.robot.Constants.LED_STATE;
5454
import frc.robot.Constants.NOTE_POSITIONS;
5555
import frc.robot.subsystems.led.LED;
56+
import frc.robot.util.AllianceFlipUtil;
5657
import frc.robot.util.FieldConstants;
5758
import frc.robot.util.LimelightHelpers;
5859
import frc.robot.util.LimelightHelpers.PoseEstimate;
@@ -697,17 +698,19 @@ public Optional<Rotation2d> turnToSpeakerAngle() {
697698
return Optional.empty();
698699
}
699700

700-
public Command generateTrajectory(
701-
Pose2d target,
701+
public PathPlannerPath generateTrajectory(
702+
Translation2d target,
702703
double maxVelMetersPerSec,
703704
double maxAccelMetersPerSecSquared,
704705
double maxAngVelDegPerSec,
705706
double maxAngAccelDegPerSecSquared,
706707
double endVelMetersPerSec) {
708+
Rotation2d targetRotation =
709+
new Rotation2d(target.getX() - getPose().getX(), target.getY() - getPose().getY());
707710
List<Translation2d> points =
708711
PathPlannerPath.bezierFromPoses(
709-
new Pose2d(getPose().getY(), getPose().getX(), getPose().getRotation()),
710-
new Pose2d(target.getY(), target.getX(), target.getRotation()));
712+
new Pose2d(getPose().getX(), getPose().getY(), getPose().getRotation()),
713+
new Pose2d(target.getX(), target.getY(), AllianceFlipUtil.apply(targetRotation)));
711714
PathPlannerPath path =
712715
new PathPlannerPath(
713716
points,
@@ -716,9 +719,9 @@ public Command generateTrajectory(
716719
maxAccelMetersPerSecSquared,
717720
Units.degreesToRadians(maxAngVelDegPerSec),
718721
Units.degreesToRadians(maxAngAccelDegPerSecSquared)),
719-
new GoalEndState(endVelMetersPerSec, target.getRotation(), true));
722+
new GoalEndState(endVelMetersPerSec, AllianceFlipUtil.apply(targetRotation), true));
720723

721-
return AutoBuilder.followPath(path);
724+
return path;
722725
}
723726

724727
public void runPath(PathPlannerPath path) {

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

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

5656
static {
5757
for (int i = 0; i < spikeTranslations.length; i++) {
58-
spikeTranslations[i] = new Translation2d(spikeFirstY + (i * spikeSeparationY), spikeX);
58+
spikeTranslations[i] = new Translation2d(spikeX, spikeFirstY + (i * spikeSeparationY));
5959
}
6060
}
6161
}

0 commit comments

Comments
 (0)