Skip to content

Faster autons #54

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
125 changes: 125 additions & 0 deletions src/main/deploy/pathplanner/autos/Left2CoralSpeedy.auto
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
{
"version": "2025.0",
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "LeftCoralPre1"
}
},
{
"type": "parallel",
"data": {
"commands": [
{
"type": "named",
"data": {
"name": "RAISE_ELEVATOR_L4"
}
},
{
"type": "path",
"data": {
"pathName": "LeftCoral1"
}
}
]
}
},
{
"type": "named",
"data": {
"name": "OUTTAKE_CORAL"
}
},
{
"type": "parallel",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "LeftCoralIntakePre2"
}
},
{
"type": "named",
"data": {
"name": "LOWER_ELEVATOR"
}
}
]
}
},
{
"type": "path",
"data": {
"pathName": "LeftCoralIntake2"
}
},
{
"type": "named",
"data": {
"name": "GET_CORAL"
}
},
{
"type": "path",
"data": {
"pathName": "LeftCoralPre2"
}
},
{
"type": "parallel",
"data": {
"commands": [
{
"type": "named",
"data": {
"name": "RAISE_ELEVATOR_L4"
}
},
{
"type": "path",
"data": {
"pathName": "LeftCoral2"
}
}
]
}
},
{
"type": "named",
"data": {
"name": "OUTTAKE_CORAL"
}
},
{
"type": "parallel",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "LeftCoral2Reverse"
}
},
{
"type": "named",
"data": {
"name": "LOWER_ELEVATOR"
}
}
]
}
}
]
}
},
"resetOdom": true,
"folder": "LeftAutons",
"choreoAuto": false
}
16 changes: 8 additions & 8 deletions src/main/deploy/pathplanner/paths/LeftCoral2Reverse.path
Original file line number Diff line number Diff line change
Expand Up @@ -8,24 +8,24 @@
},
"prevControl": null,
"nextControl": {
"x": 3.4038829108808333,
"y": 5.5789732859277015
"x": 2.8895057362806864,
"y": 5.708562332187294
},
"isLocked": false,
"linkedName": "Left Coral Post 2"
},
{
"anchor": {
"x": 3.408333333333333,
"y": 5.569949494949494
"x": 1.2535353535353533,
"y": 7.003093434343434
},
"prevControl": {
"x": 3.6808130069872926,
"y": 5.096884123936249
"x": 1.820257574166762,
"y": 6.543201602037102
},
"nextControl": null,
"isLocked": false,
"linkedName": "Left Coral Pre 2"
"linkedName": "Left Source"
}
],
"rotationTargets": [],
Expand All @@ -42,7 +42,7 @@
},
"goalEndState": {
"velocity": 0,
"rotation": -59.99999999999999
"rotation": -52.2243156940453
},
"reversed": false,
"folder": "LeftPaths",
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ public static final class ElevatorConstants {
public static final double kElevatorSensorMaxTrustDistance = 10;

public static final double kL1Height = 0.2;
public static final double kL2Height = 3;
public static final double kL2Height = 3.25;
public static final double kL3Height = 10.5;
public static final double kL4Height = 20;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ public CoralL3Command(EndEffectorSubsystem endEffector, ElevatorSubsystem elevat
new ParallelCommandGroup(
new PivotCommand(endEffector, 0.36),
new ElevatorNoPivotCommand(ElevatorConstants.kL3Height, elevator)),
new PivotCommand(endEffector, 1.035)
new PivotCommand(endEffector, 0.9)
);
}

Expand Down
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/utils/FindNearest.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,18 @@ public class FindNearest {

// Scoring locations for the blue alliance
public static final Pose2d[] blueScoringLocations = {
new Pose2d(new Translation2d(5.759, 3.952), Rotation2d.fromDegrees(180)),
new Pose2d(new Translation2d(5.36, 3.03), Rotation2d.fromDegrees(120)),
new Pose2d(new Translation2d(5.042, 2.88), Rotation2d.fromDegrees(120)),
new Pose2d(new Translation2d(4.035, 2.794), Rotation2d.fromDegrees(60)),
new Pose2d(new Translation2d(3.80, 2.95), Rotation2d.fromDegrees(60)),
new Pose2d(new Translation2d(3.222, 3.738), Rotation2d.fromDegrees(0)),
new Pose2d(new Translation2d(3.218, 4.015), Rotation2d.fromDegrees(0)),
new Pose2d(new Translation2d(3.638, 5.004), Rotation2d.fromDegrees(-60)),
new Pose2d(new Translation2d(3.94, 5.14), Rotation2d.fromDegrees(-60)),
new Pose2d(new Translation2d(4.95, 5.227), Rotation2d.fromDegrees(-120)),
new Pose2d(new Translation2d(5.247, 4.993), Rotation2d.fromDegrees(-120)),
new Pose2d(new Translation2d(5.759, 4.269), Rotation2d.fromDegrees(180))
new Pose2d(new Translation2d(5.778, 3.861), Rotation2d.fromDegrees(180)),
new Pose2d(new Translation2d(5.276, 2.993), Rotation2d.fromDegrees(120)),
new Pose2d(new Translation2d(4.99, 2.828), Rotation2d.fromDegrees(120)),
new Pose2d(new Translation2d(3.988, 2.828), Rotation2d.fromDegrees(60)),
new Pose2d(new Translation2d(3.702, 2.993), Rotation2d.fromDegrees(60)),
new Pose2d(new Translation2d(3.200, 3.861), Rotation2d.fromDegrees(0)),
new Pose2d(new Translation2d(3.200, 4.191), Rotation2d.fromDegrees(0)),
new Pose2d(new Translation2d(3.702, 5.059), Rotation2d.fromDegrees(-60)),
new Pose2d(new Translation2d(3.988, 5.224), Rotation2d.fromDegrees(-60)),
new Pose2d(new Translation2d(4.99, 5.224), Rotation2d.fromDegrees(-120)),
new Pose2d(new Translation2d(5.276, 5.059), Rotation2d.fromDegrees(-120)),
new Pose2d(new Translation2d(5.778, 4.191), Rotation2d.fromDegrees(180))
};

// Scoring locations for the red alliance
Expand Down