Skip to content

Commit

Permalink
Add New Path and Clean Up Names in GUI
Browse files Browse the repository at this point in the history
  • Loading branch information
Java4First committed Mar 30, 2024
1 parent 6a0df50 commit fd83d8d
Show file tree
Hide file tree
Showing 5 changed files with 130 additions and 22 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
{
"version": 1.0,
"startingPose": {
"position": {
"x": 0.5,
"y": 6.97
},
"rotation": 0.0
},
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "named",
"data": {
"name": "Delay Auto Start"
}
},
{
"type": "path",
"data": {
"pathName": "Narrow Path 01"
}
},
{
"type": "named",
"data": {
"name": "Shoot Auto AMP w/ Pre-Load"
}
},
{
"type": "wait",
"data": {
"waitTime": 1.0
}
},
{
"type": "path",
"data": {
"pathName": "Narrow Path 01 Return"
}
}
]
}
},
"folder": null,
"choreoAuto": false
}
52 changes: 52 additions & 0 deletions src/main/deploy/pathplanner/paths/Narrow Path 01 Return.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 1.54,
"y": 6.42
},
"prevControl": null,
"nextControl": {
"x": 1.562418342251094,
"y": 6.42
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 0.5,
"y": 7.15
},
"prevControl": {
"x": 0.5999999999999996,
"y": 7.15
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 1.5,
"maxAcceleration": 1.5,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0,
"rotation": 0.0,
"rotateFast": false
},
"reversed": false,
"folder": "Adam",
"previewStartingState": {
"rotation": 0,
"velocity": 0
},
"useDefaultConstraints": true
}
51 changes: 29 additions & 22 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ void configurePathPlannerCommands() {
NamedCommands.registerCommand(
"Shoot Auto AMP w/ Pre-Load",
Commands.sequence(
new WaitCommand(1.0),
new WaitCommand(0.5),
m_mast.setTask(Mast.Task.LAUNCHSUB),
m_launcher.setTask(Launcher.Task.LAUNCHSUB),
new WaitUntilCommand(m_launcher::atSpeed),
Expand All @@ -386,7 +386,7 @@ void configurePathPlannerCommands() {
NamedCommands.registerCommand(
"Shoot Auto Note 1 w/ Pre-Load",
Commands.sequence(
new WaitCommand(1.0),
new WaitCommand(0.5),
m_mast.setTask(Mast.Task.LAUCNHNOTE1),
m_launcher.setTask(Launcher.Task.LAUCNHNOTE1),
new WaitUntilCommand(m_launcher::atSpeed),
Expand All @@ -395,7 +395,7 @@ void configurePathPlannerCommands() {
NamedCommands.registerCommand(
"Shoot Auto Note 2 w/ Pre-Load",
Commands.sequence(
new WaitCommand(1.0),
new WaitCommand(0.5),
m_mast.setTask(Mast.Task.LAUCNHNOTE2),
m_launcher.setTask(Launcher.Task.LAUCNHNOTE2),
new WaitUntilCommand(m_launcher::atSpeed),
Expand Down Expand Up @@ -451,9 +451,10 @@ private enum AutoSelection {
//
// STU
//
narrowShootAuto("Narrow 1 Note Shoot Auto", "Narrow 1 Note Shoot Auto"),
narrowShootScootAuto("Narrow 1 Note Shoot Scoot Auto", "Narrow 1 Note Shoot Scoot Auto"),
narrowShootReturnAuto("Narrow 1 Note Shoot Return Auto", "Narrow 1 Note Shoot Return Auto"),
middleSitStillShootAuto("Middle Sit Still Shoot Auto", "Middle Sit Still Shoot Auto"),
wideShootAuto("Wide Shoot Auto", "Wide Shoot Auto");
wideShootScootAuto("Wide 1 Note Shoot Scoot Auto", "Wide 1 Note Shoot Scoot Auto");
// @formatter:on

private final String name;
Expand Down Expand Up @@ -486,6 +487,24 @@ public void createAutoChooser() {
// Default option is safety of "do nothing"
autoChooser.setDefaultOption("Do Nothing", AutoSelection.doNothing);

/** Adam's Autos */

/** Shoot w/ Starting Note & Then Pick-Up and Shoot Two Notes */
autoChooser.addOption("[A] Narrow 3 Notes Shoot", AutoSelection.narrowAdamShootAuto);
/** */
autoChooser.addOption("[A] Narrow 2 Notes Climb", AutoSelection.narrowAdamClimbAuto);

/** Stu's Autos */

/** Simple Shoot w/ Starting Note */
autoChooser.addOption("[S] Narrow Shoot & Scoot", AutoSelection.narrowShootScootAuto);
//
autoChooser.addOption("[S] Narrow Shoot & Return", AutoSelection.narrowShootReturnAuto);
//
autoChooser.addOption("[S] Middle Sit & Shoot", AutoSelection.middleSitStillShootAuto);
//
autoChooser.addOption("[S] Wide Shoot & Scoot", AutoSelection.wideShootScootAuto);

/** Test */
//
autoChooser.addOption("Simple Test", AutoSelection.simpleTest);
Expand All @@ -496,30 +515,14 @@ public void createAutoChooser() {
//
autoChooser.addOption("Sit Still", AutoSelection.sitStill);
//
autoChooser.addOption("Sit Still and Shoot", AutoSelection.sitStillShootAuto);
autoChooser.addOption("Sit Still & Shoot", AutoSelection.sitStillShootAuto);

/** Drive */
//
// autoChooser.addOption("Simple BACKWARD", AutoSelection.doSimpleBackward);
//
// autoChooser.addOption("Simple FORWARD", AutoSelection.doSimpleForward);

/** Adam's Autos */

/** Shoot w/ Starting Note & Then Pick-Up and Shoot Two Notes */
autoChooser.addOption("[A] Narrow 3 Notes Shoot", AutoSelection.narrowAdamShootAuto);
/** */
autoChooser.addOption("[A] Narrow 2 Notes Climb", AutoSelection.narrowAdamClimbAuto);

/** Stu's Autos */

/** Simple Shoot w/ Starting Note */
autoChooser.addOption("[S] Narrow Scoot & Shoot", AutoSelection.narrowShootAuto);
//
autoChooser.addOption("[S] Middle Sit & Shoot", AutoSelection.middleSitStillShootAuto);
//
autoChooser.addOption("[S] Wide Scoot & Shoot", AutoSelection.wideShootAuto);

// Put the chooser on the dashboard
SmartDashboard.putData("Auto Chooser", autoChooser);
}
Expand Down Expand Up @@ -564,6 +567,10 @@ public void createAutoDelayChooser() {
autoDelayChooser.addOption("8 Sec", Integer.valueOf(8));
autoDelayChooser.addOption("9 Sec", Integer.valueOf(9));
autoDelayChooser.addOption("10 Sec", Integer.valueOf(10));
autoDelayChooser.addOption("11 Sec", Integer.valueOf(11));
autoDelayChooser.addOption("12 Sec", Integer.valueOf(12));
autoDelayChooser.addOption("13 Sec", Integer.valueOf(13));
autoDelayChooser.addOption("14 Sec", Integer.valueOf(14));

// Put the chooser on the dashboard
SmartDashboard.putData("Auto Delay Chooser", autoDelayChooser);
Expand Down

0 comments on commit fd83d8d

Please sign in to comment.