Skip to content

Commit

Permalink
Final changes
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Mar 23, 2024
1 parent 9d7c279 commit 590100a
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 12 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,8 @@ public static final class IntakeConstants {

public static final double kIntakeSpeed = 0.5;

// public static final int kProximityThreshold = 130;
public static final int kIRThreshold = 2;
public static final int kProximityThreshold = 130;
// public static final int kIRThreshold = 2;
}

public static final class ShooterConstants {
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -227,14 +227,14 @@ private void configureBindings() {
return m_operatorController.getBButton() && m_operatorController.getRightBumper();
}).whileTrue(new InstantCommand(() -> m_climberSubsystem.reverse()));

// Toggle Distance Sensor, Operator Controller Left Bumper + Start Button
// Toggle Color Sensor, Operator Controller Left Bumper + Start Button
new Trigger(() -> {
return m_operatorController.getLeftBumper() && m_operatorController.getStartButton();
}).onTrue(new InstantCommand(() -> m_intakeSubsystem.colorSensorToggle()));

// Toggle Compressor, Operator Controller Right Bumper + Menu
// Toggle Compressor, Operator Controller Right Bumper + Back Button
new Trigger(() -> {
return m_operatorController.getRightBumper() && m_operatorController.getStartButton();
return m_operatorController.getLeftBumper() && m_operatorController.getBackButton();
}).onTrue(new InstantCommand(() -> m_climberSubsystem.toggleCompressor()));
}

Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ public void periodic() {
m_rightSolenoid.set(m_state);
SmartDashboard.putString("pneumatics state", m_state.name());
SmartDashboard.putNumber("pressure", m_pHub.getPressure(0));
SmartDashboard.putBoolean("Compressor Enabled", m_compressorEnabled);
SmartDashboard.putBoolean("Compressor Running", m_pHub.getCompressor());
}

/**
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ public class IntakeSubsystem extends SubsystemBase {
/** Creates a new IntakeSubsystem */
public IntakeSubsystem() {
m_armEncoder.setPositionOffset(IntakeConstants.kArmEncoderOffset);
SmartDashboard.putNumber("arm", m_armEncoder.getAbsolutePosition());
m_armEncoder.setDistancePerRotation(360);

m_intakeMotor.setIdleMode(IdleMode.kCoast);
Expand Down Expand Up @@ -97,13 +96,13 @@ public void stopIntake() {
/**
* Gets distance from Color sensor
*/
public int getColorIR() {
return m_colorSensor.getIR();
public int getColorProximity() {
return m_colorSensor.getProximity();
}

@Override
public void periodic() {
haveNote = getColorIR() > IntakeConstants.kIRThreshold;
haveNote = m_colorSensorToggle ? getColorProximity() > IntakeConstants.kProximityThreshold : false;

double armMotorSpeed = MathUtil.clamp(m_armPID.calculate(m_armEncoder.getDistance(), m_armSetpoint), -0.3, 0.3);
m_armMotor.set(armMotorSpeed);
Expand All @@ -113,7 +112,8 @@ public void periodic() {
SmartDashboard.putNumber("Arm Absolute Angle", m_armEncoder.getAbsolutePosition());
SmartDashboard.putBoolean("Have Note?", haveNote);
// SmartDashboard.putNumber("pid output", armMotorSpeed);
SmartDashboard.putNumber("Proximity", getColorIR());
SmartDashboard.putNumber("Proximity", m_colorSensor.getProximity());
SmartDashboard.putBoolean("Color Sensor Toggle", m_colorSensorToggle);
SmartDashboard.putNumber("IR", m_colorSensor.getIR());
}

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,8 @@ public double returnCurrentSpeed() {
@Override
public void periodic() {
// This method will be called once per scheduler run
SmartDashboard.putNumber("bottom Speed", m_bottomSpeed);
SmartDashboard.putNumber("top Speed", m_topSpeed);
// SmartDashboard.putNumber("bottom Speed", m_bottomSpeed);
// SmartDashboard.putNumber("top Speed", m_topSpeed);

m_bottom.set(m_bottomSpeed);
m_top.set(m_topSpeed);
Expand Down

0 comments on commit 590100a

Please sign in to comment.