Skip to content

Commit

Permalink
balls hehehe
Browse files Browse the repository at this point in the history
  • Loading branch information
pratyush-p committed Nov 17, 2022
1 parent ab43233 commit 1f77f42
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/commands/JoystickSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ public class JoystickSwerve extends CommandBase {
private XboxController joy;
private SwerveDrive swerve;
private Limelight limelight;
private int controlMode;

public JoystickSwerve () {
joy = RobotContainer.getController();
Expand Down
15 changes: 8 additions & 7 deletions src/main/java/frc/robot/subsystems/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ public void stopMods() {

public SwerveModuleState[] controllerToModuleStates(XboxController controller, Limelight limelight) {
dampener = ((Constants.DAMPENER_LOW_PERCENT - 1) * controller.getLeftTriggerAxis() + 1);
double visionDampener = controller.getRightTriggerAxis();
double shootButton = controller.getRightTriggerAxis();
boolean targetVis = limelight.targetVisible();

xSpeed = -controller.getLeftX() * dampener;
Expand All @@ -108,36 +108,37 @@ public SwerveModuleState[] controllerToModuleStates(XboxController controller, L
xSpeed = Math.sin(Math.toRadians(360 - controller.getPOV())) * dampener;
}

if (visionDampener > .1) {

if (shootButton > .1) {
if (targetVis) {
double visionSpeed = faceTargetPID.calculate(limelight.targetX(), new State(0, 0));
if (faceTargetPID.atGoal()) {
resetTargetingPID(limelight.targetX(), Math.toDegrees(visionSpeed));
setGyroOffset(OdometryMath2022.gyroTargetOffset()); //
setGyroOffset(OdometryMath2022.gyroTargetOffset()); //might need to negate
}
if (visionDampener > .9) {
if (shootButton > .9) {
x2Speed = visionSpeed;
} else {
// x2Speed = x2Speed * (1 - visionDampener) + visionSpeed * visionDampener;
// x2Speed = x2Speed * (1 - shootButton) + visionSpeed * shootButton;
x2Speed = visionSpeed;
}
} else {
x2Speed = xRateLimiter2.calculate(OdometryMath2022.robotEasiestTurnToTarget()) * Constants.MAX_ANGULAR_SPEED_TELEOP_RAD_PER_S * 2;
}
}


chassisSpeeds = isFieldRelative ? ChassisSpeeds.fromFieldRelativeSpeeds(ySpeed, xSpeed, x2Speed, getPose().getRotation()) : new ChassisSpeeds(ySpeed, xSpeed, x2Speed);

//IF YOU ARE WONDERING WHY YSPEED IS IN XSPEED PARAM OF CHASSIS SPEEDS STOP WHAT YOU ARE DOING AND ASK PRAT.
//DO NOT FLIP.
//WILL BREAK SPACE TIME FABRIC.
//DUCK WILL NOT BE PROUD.

//DO NOT CHANGE ANYTHING HERE
//DO NOT CHANGE ANYTHING HERE WITHOUT ASKING PRAT
//EVER
//THIS IS SACRED CODE
//IT WAS WRITTEN 35000 FEET IN THE AIR TRAVELING AT 582 MILES PER HOUR
//AND WAS LATER EDITED 35000 FEET IN THE AIR TRAVELING AT 620 MILES PER HOUR

SwerveModuleState[] states = Constants.SWERVE_DRIVE_KINEMATICS.toSwerveModuleStates(chassisSpeeds);

Expand Down

0 comments on commit 1f77f42

Please sign in to comment.