Skip to content

Commit

Permalink
bordie day 1
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Oct 6, 2024
1 parent d084d28 commit 498e2c1
Show file tree
Hide file tree
Showing 4 changed files with 57 additions and 30 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ public static final class IntakeConstants {
public static final double kIntakeAmpScoringAngle = -71; // 193 - 100 (previous angle)

/** Encoder offset in rotations */
public static final double kArmEncoderOffset = 0.715;
public static final double kArmEncoderOffset = 0.259;

public static final double kIntakeSpeed = 0.5;

Expand Down
17 changes: 15 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -207,13 +207,26 @@ private void configureBindings() {
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, ShooterConstants.kShooterOffTime));

new JoystickButton(m_driverController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_ampServo.setAngle(90)));
.onTrue(new InstantCommand(() -> m_ampServo.setAngle(135)));

new JoystickButton(m_driverController, Button.kY.value)
.onTrue(new InstantCommand(() -> {
m_intakeSubsystem.getCurrentCommand().cancel();
m_intakeSubsystem.resetArmEncoder();
DriverStation.reportError("reset intake in", false);
}));

// new JoystickButton(m_driverController, Button.kX.value)
// .onTrue(new InstantCommand(() -> {
// // m_intakeSubsystem.getCurrentCommand().cancel();
// DriverStation.reportError("reset intake out", false);
// }));

// new JoystickButton(m_driverController, Button.kA.value)
// .onTrue(new InstantCommand(() -> m_servoSubsystem.setPulseWidth(2500)));

new JoystickButton(m_driverController, Button.kB.value)
.onTrue(new InstantCommand(() -> m_ampServo.setAngle(0)));
.onTrue(new InstantCommand(() -> m_ampServo.setAngle(-20)));

// new JoystickButton(m_driverController, Button.kB.value)
// .onTrue(new InstantCommand(() -> m_servoSubsystem.setPulseWidth(1500)));
Expand Down
55 changes: 28 additions & 27 deletions src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,72 +13,73 @@
import frc.robot.Constants.ClimberConstants;

public class ClimberSubsystem extends SubsystemBase {
private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
ClimberConstants.leftForwardChannel, ClimberConstants.leftReverseChannel);
private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
ClimberConstants.rightReverseChannel, ClimberConstants.rightForwardChannel);
private PneumaticHub m_pHub;
// private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
// ClimberConstants.leftForwardChannel, ClimberConstants.leftReverseChannel);
// private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
// ClimberConstants.rightReverseChannel, ClimberConstants.rightForwardChannel);
// private PneumaticHub m_pHub;

private boolean m_compressorEnabled;
// private boolean m_compressorEnabled;

private Value m_state;
// private Value m_state;

public ClimberSubsystem() {
m_pHub = new PneumaticHub(2);
// m_pHub = new PneumaticHub(2);

solenoidOff();
// solenoidOff();

m_compressorEnabled = false;
// m_compressorEnabled = false;
}

// Runs once every tick (~20ms)
public void periodic() {
m_leftSolenoid.set(m_state);
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());
// m_leftSolenoid.set(m_state);
// 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());
}

public void reset() {
m_state = kOff;
// m_state = kOff;
}

/**
* Sets the state of the solenoid to off
*/
public void solenoidOff() {
m_state = kOff;
// m_state = kOff;
}

/**
* Extends both arms
*/
public void forward() {
m_state = kForward;
// m_state = kForward;
}

/**
* Retracts both arms
*/
public void reverse() {
m_state = kReverse;
// m_state = kReverse;
}

public Value getState(){
return m_state;
// return m_state;
return Value.kOff;
}

/**
* Toggles the state of the compressor (on/off)
*/
public void toggleCompressor() {
m_compressorEnabled = !m_compressorEnabled;
if (m_compressorEnabled) {
m_pHub.enableCompressorAnalog(ClimberConstants.minPressure, ClimberConstants.maxPressure);
} else {
m_pHub.disableCompressor();
}
// m_compressorEnabled = !m_compressorEnabled;
// if (m_compressorEnabled) {
// m_pHub.enableCompressorAnalog(ClimberConstants.minPressure, ClimberConstants.maxPressure);
// } else {
// m_pHub.disableCompressor();
// }
}
}
13 changes: 13 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -155,4 +155,17 @@ public static enum ArmPosition {
public void colorSensorToggle() {
m_colorSensorToggle = !m_colorSensorToggle;
}

/** honestly its been a rough day i dont care enough
*
* yolo
*/
public void resetArmEncoder() {
m_armEncoder = new DutyCycleEncoder(IntakeConstants.kArmEncoderChannel);

m_armEncoder.setPositionOffset(IntakeConstants.kArmEncoderOffset);
m_armEncoder.setDistancePerRotation(360);

m_armSetpoint = m_armEncoder.getDistance();
}
}

0 comments on commit 498e2c1

Please sign in to comment.