Skip to content

Commit

Permalink
Update SwerveSubsystem.java
Browse files Browse the repository at this point in the history
Add zero the gyro with alliance method
  • Loading branch information
rickfmn authored Feb 13, 2024
1 parent 6cbb07b commit 26694ff
Showing 1 changed file with 22 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,28 @@ public void zeroGyro()
swerveDrive.zeroGyro();
}

private boolean isRedAlliance()
{
var alliance = DriverStation.getAlliance();
return alliance.isPresent() ? alliance.get() == DriverStation.Alliance.Red : false;
}

/**
* This will zero (calibrate) the robot to assume the current position is facing forward
*
* If red alliance rotate the robot 180 after the drviebase zero command
*/
public void zeroGyroWithAlliance()
{
if (isRedAlliance()) {
zeroGyro();
//Set the pose 180 degrees
resetOdometry(new Pose2d(getPose().getTranslation(), Rotation2d.fromDegrees(180)));
} else {
zeroGyro();
}
}

/**
* Sets the drive motors to brake/coast mode.
*
Expand Down

0 comments on commit 26694ff

Please sign in to comment.