Skip to content

Commit

Permalink
formatting pass
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Mar 5, 2024
1 parent 7e9f0f9 commit a3fe324
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 14 deletions.
20 changes: 11 additions & 9 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ private void configureBindings() {
.onFalse(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));
}

/**
/**
* Reset all subsystems on teleop init
*/
public void resetAllSubsystems() {
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -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() };
}

/**
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ public void setArmPosition(ArmPosition position) {
m_armPID.setSetpoint(m_armSetpoint);
}

public double getArmPosition(){
public double getArmPosition() {
return m_armSetpoint;
}

Expand Down Expand Up @@ -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);
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/subsystems/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -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<Measurement> consumer) {
m_consumerList.add(consumer);
}
Expand Down

0 comments on commit a3fe324

Please sign in to comment.