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
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -471,6 +471,7 @@ public static final class SwerveConstants {
public static final double maxTranslationalSpeed = Units.feetToMeters(14.5);
public static final double maxAngularSpeed = Units.degreesToRadians(180);
public static final double slowMotionMaxTranslationalSpeed = Units.feetToMeters(3.53);
public static final double bufferMaxTranslationalSpeed = Units.feetToMeters(1);
public static final double turboMaxTranslationalSpeed = Units.feetToMeters(14.5);

public static final double maxTranslationalAcceleration = Units.feetToMeters(18.0);
Expand Down
26 changes: 26 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
Expand Down Expand Up @@ -89,6 +90,10 @@ public class RobotContainer implements Logged {
private Alert swervePrematchAlert = new Alert("", AlertType.INFO);
private Alert generalPrematchAlert = new Alert("", AlertType.INFO);

Pose2d currentPose = swerve.getPose();
double xCoordinate = currentPose.getX();
double yCoordinate = currentPose.getY();

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
DataLogManager.log("Initializing Robot Container");
Expand Down Expand Up @@ -349,6 +354,27 @@ private void configureDriveBindings() {

driverController.x().whileTrue(swerve.run(swerve::lockModules));

if (xCoordinate > 7.5 || xCoordinate < -7.5 || yCoordinate > 5 || yCoordinate < -5) {
driverController.rumbleFor(5, RumbleType.kBothRumble, 1);
}

driverController.b().onTrue(
new TeleopSwerve(
driverController::getLeftY,
driverController::getLeftX,
driverController::getRightX,
driverController::getRightY,
driverController::getLeftBumper,
() -> {
if (xCoordinate > 7.5 || xCoordinate < -7.5 || yCoordinate > 5 || yCoordinate < -5) {
return SwerveConstants.bufferMaxTranslationalSpeed;
}
return SwerveConstants.maxTranslationalSpeed;
},
SwerveConstants.maxAngularSpeed,
swerve)
);

// slowMode
// .and(turnToSpeaker.negate())
// .whileTrue(
Expand Down
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -618,6 +618,18 @@ public SwerveModuleState[] getDesiredStates() {
};
}

Pose2d currentPose = getPose();
double xCoordinate = currentPose.getX();
double yCoordinate = currentPose.getY();

public boolean isPracticeOutOfBounds() {
if (xCoordinate > 7.5 || xCoordinate < -7.5 || yCoordinate > 5 || yCoordinate < -5) {
return true;
} else {
return false;
}
}

private boolean odometryUpdateValid(Twist2d delta) {
Pose2d poseExponential = new Pose2d().exp(delta);

Expand Down