-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
11 changed files
with
492 additions
and
18 deletions.
There are no files selected for viewing
65 changes: 65 additions & 0 deletions
65
src/main/deploy/pathplanner/paths/New New New New New New Path.path
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,65 @@ | ||
{ | ||
"version": 1.0, | ||
"waypoints": [ | ||
{ | ||
"anchor": { | ||
"x": 2.9121061779449953, | ||
"y": 6.983739254587885 | ||
}, | ||
"prevControl": null, | ||
"nextControl": { | ||
"x": 3.9121061779449935, | ||
"y": 6.483739254587885 | ||
}, | ||
"isLocked": false, | ||
"linkedName": null | ||
}, | ||
{ | ||
"anchor": { | ||
"x": 5.0, | ||
"y": 5.0 | ||
}, | ||
"prevControl": { | ||
"x": 4.0, | ||
"y": 6.0 | ||
}, | ||
"nextControl": { | ||
"x": 6.0, | ||
"y": 4.0 | ||
}, | ||
"isLocked": false, | ||
"linkedName": null | ||
}, | ||
{ | ||
"anchor": { | ||
"x": 7.0, | ||
"y": 1.0 | ||
}, | ||
"prevControl": { | ||
"x": 6.75, | ||
"y": 2.5 | ||
}, | ||
"nextControl": null, | ||
"isLocked": false, | ||
"linkedName": null | ||
} | ||
], | ||
"rotationTargets": [], | ||
"constraintZones": [], | ||
"eventMarkers": [], | ||
"globalConstraints": { | ||
"maxVelocity": 3.5, | ||
"maxAcceleration": 3.0, | ||
"maxAngularVelocity": 270.0, | ||
"maxAngularAcceleration": 600.0 | ||
}, | ||
"goalEndState": { | ||
"velocity": 0, | ||
"rotation": 0, | ||
"rotateFast": false | ||
}, | ||
"reversed": false, | ||
"folder": null, | ||
"previewStartingState": null, | ||
"useDefaultConstraints": false | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
186 changes: 186 additions & 0 deletions
186
src/main/kotlin/com/team4099/robot2023/auto/mode/FourNoteAutoPathWithFirstCenterSide.kt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,186 @@ | ||
package com.team4099.robot2023.auto.mode | ||
|
||
import com.team4099.lib.trajectory.FieldWaypoint | ||
import com.team4099.robot2023.commands.drivetrain.DrivePathCommand | ||
import com.team4099.robot2023.config.constants.FlywheelConstants | ||
import com.team4099.robot2023.subsystems.drivetrain.drive.Drivetrain | ||
import com.team4099.robot2023.subsystems.superstructure.Superstructure | ||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup | ||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup | ||
import edu.wpi.first.wpilibj2.command.WaitCommand | ||
import org.team4099.lib.geometry.Pose2d | ||
import org.team4099.lib.geometry.Translation2d | ||
import org.team4099.lib.units.base.inSeconds | ||
import org.team4099.lib.units.base.inches | ||
import org.team4099.lib.units.base.meters | ||
import org.team4099.lib.units.derived.degrees | ||
import org.team4099.lib.units.derived.inRotation2ds | ||
|
||
class FourNoteAutoPathWithFirstCenterSide(val drivetrain: Drivetrain, val superstructure: Superstructure) : | ||
SequentialCommandGroup() { | ||
init { | ||
addRequirements(drivetrain, superstructure) | ||
|
||
addCommands( | ||
superstructure.prepSpeakerLowCommand(), | ||
superstructure.scoreCommand().withTimeout(0.5), | ||
WaitCommand(0.5), | ||
ParallelCommandGroup( | ||
DrivePathCommand.createPathInFieldFrame( | ||
drivetrain, | ||
{ | ||
listOf( | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d( | ||
((1.43.meters) + (2.34.meters + 0.3.meters)) / 2 + | ||
0.25.meters, | ||
5.55.meters | ||
) | ||
.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(2.34.meters + 0.3.meters + 0.25.meters, 5.535.meters) | ||
.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d( | ||
((1.43.meters) + (2.34.meters + 0.3.meters)) / 2 + | ||
0.25.meters, | ||
5.45.meters | ||
) | ||
.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
) // Subwoofer | ||
) | ||
} | ||
) | ||
.withTimeout(3.235 + 0.5), | ||
WaitCommand(0.3).andThen(superstructure.groundIntakeCommand()) | ||
), | ||
superstructure.prepSpeakerLowCommand(), | ||
superstructure | ||
.scoreCommand() | ||
.withTimeout(FlywheelConstants.SPEAKER_SCORE_TIME.inSeconds + 0.5), | ||
WaitCommand(FlywheelConstants.SPEAKER_SCORE_TIME.inSeconds), | ||
ParallelCommandGroup( | ||
DrivePathCommand.createPathInFieldFrame( | ||
drivetrain, | ||
{ | ||
listOf( | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), // Subwoofer | ||
FieldWaypoint( | ||
Translation2d(2.41.meters - 0.4.meters, 4.4.meters).translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(2.41.meters, 4.1.meters).translation2d, | ||
0.degrees.inRotation2ds, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
) | ||
) | ||
} | ||
) | ||
.withTimeout(3.235 + 0.5), | ||
WaitCommand(0.5).andThen(superstructure.groundIntakeCommand()) | ||
), | ||
superstructure.prepSpeakerLowCommand(), | ||
superstructure | ||
.scoreCommand() | ||
.withTimeout(FlywheelConstants.SPEAKER_SCORE_TIME.inSeconds + 0.5), | ||
WaitCommand(FlywheelConstants.SPEAKER_SCORE_TIME.inSeconds), | ||
ParallelCommandGroup( | ||
DrivePathCommand.createPathInFieldFrame( | ||
drivetrain, | ||
{ | ||
listOf( | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
startingPose.rotation.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(2.91.meters - 0.75.meters, 6.9.meters) | ||
.translation2d, | ||
null, | ||
180.degrees.inRotation2ds, | ||
), | ||
FieldWaypoint( | ||
Translation2d(2.91.meters - 0.25.meters, 7.1.meters).translation2d, | ||
0.degrees.inRotation2ds, | ||
180.degrees.inRotation2ds, | ||
), | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
) | ||
) | ||
} | ||
) | ||
.withTimeout(3.235 + 0.5), | ||
WaitCommand(0.5).andThen(superstructure.groundIntakeCommand()) | ||
), | ||
superstructure.prepSpeakerLowCommand(), | ||
superstructure | ||
.scoreCommand() | ||
.withTimeout(FlywheelConstants.SPEAKER_SCORE_TIME.inSeconds + 0.5), | ||
ParallelCommandGroup( | ||
DrivePathCommand.createPathInFieldFrame( | ||
drivetrain, | ||
{ | ||
listOf( | ||
FieldWaypoint( | ||
startingPose.translation.translation2d, null, 180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(4.35.meters, 4.85.meters).translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(5.92.meters, 3.9.meters).translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
), | ||
FieldWaypoint( | ||
Translation2d(8.29.meters, 4.09.meters).translation2d, | ||
null, | ||
180.degrees.inRotation2ds | ||
) | ||
) | ||
} | ||
), | ||
WaitCommand(1.0).andThen(superstructure.groundIntakeCommand()) | ||
) | ||
) | ||
} | ||
|
||
companion object { | ||
val startingPose = Pose2d(Translation2d(1.42.meters + 1.inches, 5.535.meters), 180.degrees) | ||
} | ||
} |
Oops, something went wrong.