Skip to content

Commit

Permalink
spotlessApply
Browse files Browse the repository at this point in the history
  • Loading branch information
BrownGenius committed Apr 5, 2024
1 parent 36ca114 commit 170d34f
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 11 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/config/RobotConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ public static class DriveConstants {

public static double blueSpeakerX = 0.14;
public static double speakerY = 5.53;
public static double redSpeakerX = 16.54-0.14;
public static double redSpeakerX = 16.54 - 0.14;
}

public static class ArmConstants {
Expand Down
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
package frc.robot.subsystems.drive;

import java.util.Optional;

import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.wpilibj2.command.Command;
import java.util.Optional;

public interface Drive {
/**
Expand Down
18 changes: 12 additions & 6 deletions src/main/java/frc/robot/subsystems/drive/DriveIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import edu.wpi.first.math.geometry.Pose2d;
import frc.robot.config.RobotConfig.DriveConstants;
import frc.robot.util.DevilBotState;

import org.littletonrobotics.junction.AutoLog;
import swervelib.SwerveDrive;

Expand All @@ -23,11 +22,18 @@ public void updateInputs(DriveIOInputs inputs, SwerveDrive swerveDrive) {
inputs.poseX = inputs.pose.getTranslation().getX();
inputs.poseY = inputs.pose.getTranslation().getY();
inputs.poseRotInDegrees = inputs.pose.getRotation().getDegrees();
if(!DevilBotState.isRedAlliance()){
inputs.distanceFromSpeaker = Math.sqrt(Math.pow(inputs.poseX - DriveConstants.blueSpeakerX,2)+Math.pow(inputs.poseY - DriveConstants.speakerY,2));
} else{
inputs.distanceFromSpeaker = Math.sqrt(Math.pow(inputs.poseX - DriveConstants.redSpeakerX,2)+Math.pow(inputs.poseY - DriveConstants.speakerY,2));
} ;
if (!DevilBotState.isRedAlliance()) {
inputs.distanceFromSpeaker =
Math.sqrt(
Math.pow(inputs.poseX - DriveConstants.blueSpeakerX, 2)
+ Math.pow(inputs.poseY - DriveConstants.speakerY, 2));
} else {
inputs.distanceFromSpeaker =
Math.sqrt(
Math.pow(inputs.poseX - DriveConstants.redSpeakerX, 2)
+ Math.pow(inputs.poseY - DriveConstants.speakerY, 2));
}
;
}

// Other methods for controlling the drive subsystem...
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
import frc.robot.util.DevilBotState;
import java.io.File;
import java.util.Optional;

import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import swervelib.SwerveDrive;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/util/DevilBotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ public static Optional<Double> getArmAngleToTarget() {

return armAngle;
} else {
distanceToTarget =RobotConfig.drive.getDistanceFromSpeaker();
distanceToTarget = RobotConfig.drive.getDistanceFromSpeaker();
if (distanceToTarget.isPresent()) {
Optional<Double> armAngle =
RobotConfig.instance.getArmAngleFromDistance(distanceToTarget.get());
Expand Down

0 comments on commit 170d34f

Please sign in to comment.