Skip to content

Commit 2b0b7dd

Browse files
committed
add right autos
1 parent 29015bb commit 2b0b7dd

File tree

8 files changed

+132
-66
lines changed

8 files changed

+132
-66
lines changed

src/main/deploy/pathplanner/autos/3 coral auto.auto renamed to src/main/deploy/pathplanner/autos/3 left coral auto.auto

File renamed without changes.
Lines changed: 79 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
{
2+
"version": "2025.0",
3+
"command": {
4+
"type": "sequential",
5+
"data": {
6+
"commands": [
7+
{
8+
"type": "named",
9+
"data": {
10+
"name": "lift to L4 no wait"
11+
}
12+
},
13+
{
14+
"type": "named",
15+
"data": {
16+
"name": "auto align first coral right"
17+
}
18+
},
19+
{
20+
"type": "named",
21+
"data": {
22+
"name": "score coral"
23+
}
24+
},
25+
{
26+
"type": "path",
27+
"data": {
28+
"pathName": "3a to intake (bottom)"
29+
}
30+
},
31+
{
32+
"type": "named",
33+
"data": {
34+
"name": "wait for intake"
35+
}
36+
},
37+
{
38+
"type": "named",
39+
"data": {
40+
"name": "auto align second coral right"
41+
}
42+
},
43+
{
44+
"type": "named",
45+
"data": {
46+
"name": "score coral"
47+
}
48+
},
49+
{
50+
"type": "path",
51+
"data": {
52+
"pathName": "5a to intake (bottom)"
53+
}
54+
},
55+
{
56+
"type": "named",
57+
"data": {
58+
"name": "wait for intake"
59+
}
60+
},
61+
{
62+
"type": "named",
63+
"data": {
64+
"name": "auto align third coral right"
65+
}
66+
},
67+
{
68+
"type": "named",
69+
"data": {
70+
"name": "score coral"
71+
}
72+
}
73+
]
74+
}
75+
},
76+
"resetOdom": true,
77+
"folder": null,
78+
"choreoAuto": false
79+
}

src/main/deploy/pathplanner/paths/3a to intake (bottom).path

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@
88
},
99
"prevControl": null,
1010
"nextControl": {
11-
"x": 4.597171612639926,
12-
"y": 1.8284788217117534
11+
"x": 4.342147801948673,
12+
"y": 2.2841712101516665
1313
},
1414
"isLocked": false,
1515
"linkedName": null
@@ -20,8 +20,8 @@
2020
"y": 0.5991438356164384
2121
},
2222
"prevControl": {
23-
"x": 2.570197644281619,
24-
"y": 2.148423016039245
23+
"x": 1.553166481093129,
24+
"y": 0.6440604747572632
2525
},
2626
"nextControl": null,
2727
"isLocked": false,

src/main/deploy/pathplanner/paths/5a to intake (bottom).path

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,16 +16,16 @@
1616
},
1717
{
1818
"anchor": {
19-
"x": 1.5365544105643658,
20-
"y": 0.774194700326492
19+
"x": 1.3072345890410957,
20+
"y": 0.5991438356164384
2121
},
2222
"prevControl": {
23-
"x": 1.7438561605443255,
24-
"y": 0.9222418133681778
23+
"x": 1.5145363390210553,
24+
"y": 0.7471909486581242
2525
},
2626
"nextControl": null,
2727
"isLocked": false,
28-
"linkedName": null
28+
"linkedName": "intake coral"
2929
}
3030
],
3131
"rotationTargets": [],

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

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

src/main/java/frc/robot/Constants.java

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -221,14 +221,19 @@ public static class NamedCommands {
221221
public static final String AUTO_FIRST_LEFT_CORAL_ALIGN_COMMAND_NAME = "auto align first coral left";
222222
public static final String AUTO_SECOND_LEFT_CORAL_ALIGN_COMMAND_NAME = "auto align second coral left";
223223
public static final String AUTO_THIRD_LEFT_CORAL_ALIGN_COMMAND_NAME = "auto align third coral left";
224+
public static final String AUTO_FIRST_RIGHT_CORAL_ALIGN_COMMAND_NAME = "auto align first coral right";
225+
public static final String AUTO_SECOND_RIGHT_CORAL_ALIGN_COMMAND_NAME = "auto align second coral right";
226+
public static final String AUTO_THIRD_RIGHT_CORAL_ALIGN_COMMAND_NAME = "auto align third coral right";
224227
}
225228

226229
public static class AutoNames {
227230
public static final Pair<String, String> TEST_AUTO_NAME =
228231
new Pair<String, String>("test auto", "test auto");
229232
public static final Pair<String, String> PRELOAD_1A_AUTO_NAME =
230233
new Pair<String, String>("preload to 1a", "preload to 1a");
231-
public static final Pair<String, String> THREE_CORAL_AUTO_NAME =
232-
new Pair<String, String>("three coral auto", "three coral auto");
234+
public static final Pair<String, String> THREE_LEFT_CORAL_AUTO_NAME =
235+
new Pair<String, String>("3 left coral auto", "3 left coral auto");
236+
public static final Pair<String, String> THREE_RIGHT_CORAL_AUTO_NAME =
237+
new Pair<String, String>("3 right coral auto","3 right coral auto");
233238
}
234239
}

src/main/java/frc/robot/HeadHoncho.java

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -469,6 +469,9 @@ public void bindControls(
469469
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_FIRST_LEFT_CORAL_ALIGN_COMMAND_NAME, this.autoFirstLeftCoralCommand());
470470
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_SECOND_LEFT_CORAL_ALIGN_COMMAND_NAME, this.autoSecondLeftCoralCommand());
471471
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_THIRD_LEFT_CORAL_ALIGN_COMMAND_NAME, this.autoThirdLeftCoralCommand());
472+
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_FIRST_RIGHT_CORAL_ALIGN_COMMAND_NAME, this.autoFirstRightCoralCommand());
473+
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_SECOND_RIGHT_CORAL_ALIGN_COMMAND_NAME, this.autoSecondRightCoralCommand());
474+
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_THIRD_RIGHT_CORAL_ALIGN_COMMAND_NAME, this.autoThirdRightCoralCommand());
472475
}
473476
/**
474477
* Tells the robot to move the lift to the L4 state during autonomous
@@ -610,6 +613,38 @@ public Command autoThirdLeftCoralCommand() {
610613
}
611614
}
612615

616+
public Command autoFirstRightCoralCommand() {
617+
Pose2d redAlignPose = new Pose2d(11.9, 5.1, new Rotation2d(0.0));
618+
Pose2d blueAlignPose = new Pose2d(5.6, 2.9, new Rotation2d(0.0));
619+
if (DriverStation.getAlliance().orElse(DriverStation.Alliance.Blue).equals(Alliance.Red)) {
620+
return autonomousAutoAlignToPoseCommand(redAlignPose);
621+
}
622+
else {
623+
return autonomousAutoAlignToPoseCommand(blueAlignPose);
624+
}
625+
}
626+
627+
public Command autoSecondRightCoralCommand() {
628+
Pose2d redAlignPose = new Pose2d(13.4, 5.6, new Rotation2d(0.0));
629+
Pose2d blueAlignPose = new Pose2d(4.0, 2.5, new Rotation2d(0.0));
630+
if (DriverStation.getAlliance().orElse(DriverStation.Alliance.Blue).equals(Alliance.Red)) {
631+
return autonomousAutoAlignToPoseCommand(redAlignPose);
632+
}
633+
else {
634+
return autonomousAutoAlignToPoseCommand(blueAlignPose);
635+
}
636+
}
637+
638+
public Command autoThirdRightCoralCommand() {
639+
Pose2d redAlignPose = new Pose2d(14.1, 5.2, new Rotation2d(0.0));
640+
Pose2d blueAlignPose = new Pose2d(3.45, 2.8, new Rotation2d(0.0));
641+
if (DriverStation.getAlliance().orElse(DriverStation.Alliance.Blue) == Alliance.Red) {
642+
return autonomousAutoAlignToPoseCommand(redAlignPose);
643+
}
644+
else {
645+
return autonomousAutoAlignToPoseCommand(blueAlignPose);
646+
}
647+
}
613648

614649
@Override
615650
public void periodic() {

src/main/java/frc/robot/RobotContainer.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,8 @@ private void autoModeChooser() {
139139
m_autoModeChooser.setDefaultOption("Do nothing", Commands.none());
140140
m_autoModeChooser.setDefaultOption(Constants.AutoNames.TEST_AUTO_NAME.getFirst(), new PathPlannerAuto(Constants.AutoNames.TEST_AUTO_NAME.getSecond()));
141141
m_autoModeChooser.setDefaultOption(Constants.AutoNames.PRELOAD_1A_AUTO_NAME.getFirst(), new PathPlannerAuto(Constants.AutoNames.PRELOAD_1A_AUTO_NAME.getSecond()));
142-
m_autoModeChooser.setDefaultOption(Constants.AutoNames.THREE_CORAL_AUTO_NAME.getFirst(), new PathPlannerAuto(Constants.AutoNames.THREE_CORAL_AUTO_NAME.getSecond()));
142+
m_autoModeChooser.setDefaultOption(Constants.AutoNames.THREE_LEFT_CORAL_AUTO_NAME.getFirst(), new PathPlannerAuto(Constants.AutoNames.THREE_LEFT_CORAL_AUTO_NAME.getSecond()));
143+
m_autoModeChooser.setDefaultOption(Constants.AutoNames.THREE_RIGHT_CORAL_AUTO_NAME.getFirst(), new PathPlannerAuto(Constants.AutoNames.THREE_RIGHT_CORAL_AUTO_NAME.getSecond()));
143144
PathfindingCommand.warmupCommand().schedule();
144145
}
145146

0 commit comments

Comments
 (0)