Skip to content
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

made new auton for getting 2nd note from midline needs testing #125

Closed
wants to merge 1 commit into from
Closed
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
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 1.8,
"y": 7.9
},
"prevControl": null,
"nextControl": {
"x": 2.8,
"y": 7.9
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 5.779401644273374,
"y": 7.5661179242586405
},
"prevControl": {
"x": 4.574903736702062,
"y": 7.69475362312548
},
"nextControl": {
"x": 6.983899551844681,
"y": 7.437482225391801
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 8.7,
"y": 7.4
},
"prevControl": {
"x": 8.928036011627578,
"y": 7.44677661776976
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [
{
"waypointRelativePos": 1,
"rotationDegrees": 0,
"rotateFast": false
}
],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0,
"rotation": -4.0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": -100.0,
"velocity": 0
},
"useDefaultConstraints": true
}
52 changes: 52 additions & 0 deletions src/main/deploy/pathplanner/paths/From Midline to Amp.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 8.7,
"y": 7.4
},
"prevControl": null,
"nextControl": {
"x": 9.7,
"y": 7.4
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 1.8,
"y": 7.8
},
"prevControl": {
"x": 0.8,
"y": 7.8
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0,
"rotation": -90.0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": -4.0,
"velocity": 0
},
"useDefaultConstraints": true
}
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/autons/Paths.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@
public class Paths {
public static PathPlannerPath pathFromPosition1ToAmp = PathPlannerPath.fromPathFile("From position 1 to amp");

public static PathPlannerPath pathFromAmpToMidlineWall = PathPlannerPath
.fromPathFile("Amp to midline behind notes");

public static PathPlannerPath pathFromMidlineToAmp = PathPlannerPath.fromPathFile("From Midline to Amp");

public static PathPlannerPath pathFromAmpToNote1 = PathPlannerPath.fromPathFile("From amp to top note");

public static PathPlannerPath pathFromNote1ToAmp = PathPlannerPath.fromPathFile("From note 1 to amp");
Expand Down
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/autons/ScoreInAmpMidline.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package frc.robot.autons;

import java.util.Optional;

import frc.robot.subsystems.Acquisition;
import frc.robot.subsystems.Dashboard;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import frc.robot.commands.AcquisitionRunCommand;
import frc.robot.commands.ScoreNoteCommand;
import frc.robot.commands.ScoringElevatorPositionCommand;
import frc.robot.commands.ScoringElevatorPositionCommand.FinishActions;
import frc.robot.constants.ScoringConstants.ScoringLocation;
import frc.robot.subsystems.ScoringElevator.ElevatorSetpoints;

public class ScoreInAmpMidline extends Auton {

private Acquisition acquisition = Acquisition.getInstance();

public ScoreInAmpMidline(Optional<Alliance> alliance) {
super(alliance);

Dashboard.getInstance().setTrajectory(Trajectories.getFromAmpToMidlineWallTrajectory());
this.setInitialPose(Trajectories.getFromAmpToMidlineWallTrajectory());
// try .concatenate a return and final trajectory later

super.addCommands(
followPathCommand(Paths.pathFromPosition1ToAmp),
new ScoringElevatorPositionCommand(ElevatorSetpoints.Amp, FinishActions.NoDisable),
new ScoreNoteCommand(ScoringLocation.Amp, 1.5),
new ScoringElevatorPositionCommand(ElevatorSetpoints.Ground),
new ParallelCommandGroup(
followPathCommand(Paths.pathFromAmpToMidlineWall)
.until(acquisition::isNotePresent)
.andThen(followPathCommand(Paths.pathFromMidlineToAmp)),
// new FullAcquireCommand()),
new AcquisitionRunCommand()),
new ScoringElevatorPositionCommand(ElevatorSetpoints.Amp, FinishActions.NoDisable),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i feel like this can be done while following the pathfrommidlinetoamp

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we want to make sure that the note gets all the way to top of storage as sometimes it doesnt go up right away

new ScoreNoteCommand(ScoringLocation.Amp, 3),
followPathCommand(Paths.pathFromAmpToMidlineWall));
}
}
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/autons/Trajectories.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,16 @@ public static PathPlannerTrajectory getFromPos1TaxiTrajectory() {
Rotation2d.fromDegrees(DriveTrain.getInstance().getHeading()));
}

public static PathPlannerTrajectory getFromAmpToMidlineWallTrajectory() {
return new PathPlannerTrajectory(Paths.pathFromAmpToMidlineWall, DriveTrain.getInstance().getChassisSpeeds(),
Rotation2d.fromDegrees(DriveTrain.getInstance().getHeading()));
}

public static PathPlannerTrajectory getFromMidlineToAmpTrajectory() {
return new PathPlannerTrajectory(Paths.pathFromMidlineToAmp, DriveTrain.getInstance().getChassisSpeeds(),
Rotation2d.fromDegrees(DriveTrain.getInstance().getHeading()));
}

public static PathPlannerTrajectory getFromPos2TaxiTrajectory() {
return new PathPlannerTrajectory(Paths.taxiPath2, DriveTrain.getInstance().getChassisSpeeds(),
Rotation2d.fromDegrees(DriveTrain.getInstance().getHeading()));
Expand Down
Loading