Skip to content
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
30 changes: 15 additions & 15 deletions src/main/deploy/pathplanner/paths/Example Path.path
Original file line number Diff line number Diff line change
Expand Up @@ -3,41 +3,41 @@
"waypoints": [
{
"anchor": {
"x": 4.828993187904608,
"y": 4.608670175573618
"x": 4.853401264391447,
"y": 6.951653731496711
},
"prevControl": null,
"nextControl": {
"x": 5.842276098080277,
"y": 4.136168594681116
"x": 5.093757985115818,
"y": 6.882888574602928
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 5.166769560390973,
"y": 5.0964860911203305
"x": 6.606582159745066,
"y": 7.230570582339637
},
"prevControl": {
"x": 4.166769560390973,
"y": 6.0964860911203305
"x": 6.151317312325627,
"y": 7.799255624469424
},
"nextControl": {
"x": 6.166769560390973,
"y": 4.0964860911203305
"x": 7.232336636905039,
"y": 6.4489218053173945
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 11.998469387755103,
"y": 5.416613520408163
"x": 5.312462093955592,
"y": 5.435106779399671
},
"prevControl": {
"x": 11.748469387755103,
"y": 6.916613520408162
"x": 5.411975523921398,
"y": 5.664447306250991
},
"nextControl": null,
"isLocked": false,
Expand All @@ -58,7 +58,7 @@
},
"goalEndState": {
"velocity": 0,
"rotation": 0.0
"rotation": -120.44045737256441
},
"reversed": false,
"folder": null,
Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2025-Robot-Code";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 78;
public static final String GIT_SHA = "89ac08633e9c2430feef390019719ac47b439453";
public static final String GIT_DATE = "2025-04-02 19:23:09 EDT";
public static final String GIT_BRANCH = "205-algae-pop-shot";
public static final String BUILD_DATE = "2025-04-02 20:01:00 EDT";
public static final long BUILD_UNIX_TIME = 1743638460991L;
public static final int DIRTY = 1;
public static final int GIT_REVISION = 82;
public static final String GIT_SHA = "ac86fc677adff1afe3a1c4838b99aa071515d689";
public static final String GIT_DATE = "2025-04-02 20:09:46 EDT";
public static final String GIT_BRANCH = "algae-otf";
public static final String BUILD_DATE = "2025-04-02 20:10:13 EDT";
public static final long BUILD_UNIX_TIME = 1743639013691L;
public static final int DIRTY = 0;

private BuildConstants() {}
}
14 changes: 8 additions & 6 deletions src/main/java/frc/robot/InitBindings.java
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ public static void initDriveBindings(Drive drive, StrategyManager strategyManage
|| ScoringSubsystem.getInstance().getGamePiece() == GamePiece.Algae) {
DesiredLocation desiredLocation =
ReefLineupUtil.getClosestAlgaeLocation(drive.getPose());
// drive.setDesiredIntakeLocation(desiredLocation);
drive.setDesiredIntakeLocation(desiredLocation);

// Set algae level automatically
if (ScoringSubsystem.getInstance() != null) {
Expand All @@ -214,11 +214,13 @@ public static void initDriveBindings(Drive drive, StrategyManager strategyManage
}
case Mixed:
// Start auto align if in mixed autonomy
if (ScoringSubsystem.getInstance() != null
&& ScoringSubsystem.getInstance().getGamePiece() == GamePiece.Coral) {
drive.setGoToIntake(true);
drive.fireTrigger(DriveTrigger.BeginOTF);
}
drive.setGoToIntake(true);
drive.fireTrigger(DriveTrigger.BeginOTF);
// if (ScoringSubsystem.getInstance() != null
// && ScoringSubsystem.getInstance().getGamePiece() == GamePiece.Coral) {
// drive.setGoToIntake(true);
// drive.fireTrigger(DriveTrigger.BeginOTF);
// }
// Then always start intake for scoring (no break here is intentional)
case Manual:
if (ScoringSubsystem.getInstance() != null) {
Expand Down
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/constants/field/BlueFieldLocations.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,24 @@ public class BlueFieldLocations {
public Translation2d blueReefOTF11Translation = new Translation2d(5.5, 5.6);
public Rotation2d blueReefOTF11Rotation = new Rotation2d(Math.toRadians(-120));

public Translation2d blueReefAlgaeOTF0Translation = new Translation2d(6.102, 4.034);
public Rotation2d blueReefAlgaeOTF0Rotation = new Rotation2d(Math.toRadians(-180));

public Translation2d blueReefAlgaeOTF1Translation = new Translation2d(5.322, 2.647);
public Rotation2d blueReefAlgaeOTF1Rotation = new Rotation2d(Math.toRadians(120));

public Translation2d blueReefAlgaeOTF2Translation = new Translation2d(3.667, 2.621);
public Rotation2d blueReefAlgaeOTF2Rotation = new Rotation2d(Math.toRadians(60));

public Translation2d blueReefAlgaeOTF3Translation = new Translation2d(2.879, 4.001);
public Rotation2d blueReefAlgaeOTF3Rotation = new Rotation2d(Math.toRadians(0));

public Translation2d blueReefAlgaeOTF4Translation = new Translation2d(3.661, 5.435);
public Rotation2d blueReefAlgaeOTF4Rotation = new Rotation2d(Math.toRadians(-60));

public Translation2d blueReefAlgaeOTF5Translation = new Translation2d(5.312, 5.435);
public Rotation2d blueReefAlgaeOTF5Rotation = new Rotation2d(Math.toRadians(-120));

public Translation2d blueReef0Translation = new Translation2d(5.285, 4.186);
public Translation2d blueReef1Translation = new Translation2d(5.285, 3.861);

Expand Down
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/constants/field/RedFieldLocations.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,24 @@ public class RedFieldLocations {
public Translation2d redReefOTF11Translation = new Translation2d(12.2, 2.6);
public Rotation2d redReefOTF11Rotation = new Rotation2d(Math.toRadians(60));

public Translation2d redReefAlgaeOTF0Translation = new Translation2d(11.403, 4.049);
public Rotation2d redReefAlgaeOTF0Rotation = new Rotation2d(Math.toRadians(0));

public Translation2d redReefAlgaeOTF1Translation = new Translation2d(12.232, 5.421);
public Rotation2d redReefAlgaeOTF1Rotation = new Rotation2d(Math.toRadians(-60));

public Translation2d redReefAlgaeOTF2Translation = new Translation2d(13.871, 5.421);
public Rotation2d redReefAlgaeOTF2Rotation = new Rotation2d(Math.toRadians(-120));

public Translation2d redReefAlgaeOTF3Translation = new Translation2d(14.673, 4.025);
public Rotation2d redReefAlgaeOTF3Rotation = new Rotation2d(Math.toRadians(180));

public Translation2d redReefAlgaeOTF4Translation = new Translation2d(13.921, 2.637);
public Rotation2d redReefAlgaeOTF4Rotation = new Rotation2d(Math.toRadians(120));

public Translation2d redReefAlgaeOTF5Translation = new Translation2d(12.203, 2.627);
public Rotation2d redReefAlgaeOTF5Rotation = new Rotation2d(Math.toRadians(120));

public Translation2d redReef0Translation = new Translation2d(12.273, 3.867);
public Translation2d redReef1Translation = new Translation2d(12.273, 4.187);

Expand Down
54 changes: 48 additions & 6 deletions src/main/java/frc/robot/subsystems/drive/states/OTFState.java
Original file line number Diff line number Diff line change
Expand Up @@ -61,14 +61,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF0Translation,
JsonConstants.blueFieldLocations.blueReefOTF0Rotation);
case Reef1:
case Algae0:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF1Translation,
JsonConstants.redFieldLocations.redReefOTF1Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF1Translation,
JsonConstants.blueFieldLocations.blueReefOTF1Rotation);
case Algae0:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF0Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF0Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF0Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF0Rotation);
case Reef2:
return driveInput.isAllianceRed()
? new Pose2d(
Expand All @@ -78,14 +85,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF2Translation,
JsonConstants.blueFieldLocations.blueReefOTF2Rotation);
case Reef3:
case Algae1:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF3Translation,
JsonConstants.redFieldLocations.redReefOTF3Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF3Translation,
JsonConstants.blueFieldLocations.blueReefOTF3Rotation);
case Algae1:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF1Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF1Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF1Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF1Rotation);
case Reef4:
return driveInput.isAllianceRed()
? new Pose2d(
Expand All @@ -95,14 +109,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF4Translation,
JsonConstants.blueFieldLocations.blueReefOTF4Rotation);
case Reef5:
case Algae2:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF5Translation,
JsonConstants.redFieldLocations.redReefOTF5Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF5Translation,
JsonConstants.blueFieldLocations.blueReefOTF5Rotation);
case Algae2:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF2Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF2Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF2Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF2Rotation);
case Reef6:
return driveInput.isAllianceRed()
? new Pose2d(
Expand All @@ -112,14 +133,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF6Translation,
JsonConstants.blueFieldLocations.blueReefOTF6Rotation);
case Reef7:
case Algae3:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF7Translation,
JsonConstants.redFieldLocations.redReefOTF7Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF7Translation,
JsonConstants.blueFieldLocations.blueReefOTF7Rotation);
case Algae3:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF3Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF3Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF3Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF3Rotation);
case Reef8:
return driveInput.isAllianceRed()
? new Pose2d(
Expand All @@ -129,14 +157,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF8Translation,
JsonConstants.blueFieldLocations.blueReefOTF8Rotation);
case Reef9:
case Algae4:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF9Translation,
JsonConstants.redFieldLocations.redReefOTF9Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF9Translation,
JsonConstants.blueFieldLocations.blueReefOTF9Rotation);
case Algae4:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF4Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF4Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF4Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF4Rotation);
case Reef10:
return driveInput.isAllianceRed()
? new Pose2d(
Expand All @@ -146,14 +181,21 @@ public static Pose2d findOTFPoseFromDesiredLocation(Drive driveInput) {
JsonConstants.blueFieldLocations.blueReefOTF10Translation,
JsonConstants.blueFieldLocations.blueReefOTF10Rotation);
case Reef11:
case Algae5:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefOTF11Translation,
JsonConstants.redFieldLocations.redReefOTF11Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefOTF11Translation,
JsonConstants.blueFieldLocations.blueReefOTF11Rotation);
case Algae5:
return driveInput.isAllianceRed()
? new Pose2d(
JsonConstants.redFieldLocations.redReefAlgaeOTF5Translation,
JsonConstants.redFieldLocations.redReefAlgaeOTF5Rotation)
: new Pose2d(
JsonConstants.blueFieldLocations.blueReefAlgaeOTF5Translation,
JsonConstants.blueFieldLocations.blueReefAlgaeOTF5Rotation);
case CoralStationRight:
return driveInput.isAllianceRed()
? new Pose2d(
Expand Down
Loading