From a3fe3249dfd403a7cfefe72aac4dba6e7c98b30e Mon Sep 17 00:00:00 2001 From: SR1899 Date: Mon, 4 Mar 2024 18:34:13 -0800 Subject: [PATCH] formatting pass --- src/main/java/frc/robot/Constants.java | 20 ++++++++++--------- src/main/java/frc/robot/RobotContainer.java | 2 +- .../frc/robot/subsystems/DriveSubsystem.java | 3 ++- .../frc/robot/subsystems/IntakeSubsystem.java | 4 ++-- .../frc/robot/subsystems/VisionSubsystem.java | 5 ++++- 5 files changed, 20 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 59dcb39..83599ce 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -119,16 +119,18 @@ public static final class ShooterConstants { public static final int kBottomShooterMotorPort = 35; public static final double kShooterSpeed = 0.7; public static final double kShooterOff = 0; - } + } + public static class ClimberConstants { - public final static int leftForwardChannel = 0; - public final static int rightForwardChannel = 0; - public final static int leftReverseChannel = 1; - public final static int rightReverseChannel = 1; - - public final static double minPressure = 50.0; - public final static double maxPressure = 120.0; - } + public final static int leftForwardChannel = 0; + public final static int rightForwardChannel = 0; + public final static int leftReverseChannel = 1; + public final static int rightReverseChannel = 1; + + public final static double minPressure = 50.0; + public final static double maxPressure = 120.0; + } + public static final class VisionConstants { // TODO: Update cam pose relative to center of bot public static final Pose3d kCamPose = new Pose3d(0, 0, 0, new Rotation3d(0, 0, 0)); diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 7500be3..e9bd49e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -147,7 +147,7 @@ private void configureBindings() { .onFalse(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted)); } - /** + /** * Reset all subsystems on teleop init */ public void resetAllSubsystems() { diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java index ac3160c..0ce6093 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -111,7 +111,8 @@ public void periodic() { } public void reset() { - swerveModuleStates = new SwerveModuleState[] { new SwerveModuleState(), new SwerveModuleState(), new SwerveModuleState(), new SwerveModuleState() }; + swerveModuleStates = new SwerveModuleState[] { new SwerveModuleState(), new SwerveModuleState(), + new SwerveModuleState(), new SwerveModuleState() }; } /** diff --git a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java index 8ed0a45..08eac22 100644 --- a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -73,7 +73,7 @@ public void setArmPosition(ArmPosition position) { m_armPID.setSetpoint(m_armSetpoint); } - public double getArmPosition(){ + public double getArmPosition() { return m_armSetpoint; } @@ -104,7 +104,7 @@ public double getDistanceSensor() { public void periodic() { haveNote = getDistanceSensor() < IntakeConstants.kDistanceSensorThreshold; - //Note: negative because encoder goes from 0 to -193 cuz weird + // Note: negative because encoder goes from 0 to -193 cuz weird double setMotorSpeed = MathUtil.clamp(m_armPID.calculate(m_armEncoder.getDistance(), m_armSetpoint), -0.4, 0.4); m_armMotor.set(setMotorSpeed); m_intakeMotor.set(m_intakeSpeed); diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/VisionSubsystem.java index 33fa918..3789d47 100644 --- a/src/main/java/frc/robot/subsystems/VisionSubsystem.java +++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.java @@ -70,7 +70,10 @@ public VisionSubsystem() { m_tv = m_visionNetworkTable.getIntegerTopic("tv").subscribe(0); } - /** Add a consumer, which the vision subsystem will push an update to every time there is an updated measurement */ + /** + * Add a consumer, which the vision subsystem will push an update to every time + * there is an updated measurement + */ public void addConsumer(Consumer consumer) { m_consumerList.add(consumer); }