Skip to content

Commit

Permalink
misc changes
Browse files Browse the repository at this point in the history
  • Loading branch information
team5338 committed Dec 3, 2024
1 parent c458e80 commit e2a1098
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 14 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 @@ -35,8 +35,8 @@ public static class DrivetrainConstants {
}

public static class PneumaticConstants {
public static final int kForwardChannel = 0; // TODO: Update these channel values
public static final int kReverseChannel = 2;
public static final int kForwardChannel = 2; // TODO: Update these channel values
public static final int kReverseChannel = 0;
}

public static class AutoConstants {
Expand Down
10 changes: 4 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,6 @@ public class RobotContainer {

public static final Pneumatics m_piston = new Pneumatics();
public static double speedUp = 0.0;
public static DoubleSolenoid m_doubleSolenoid = new DoubleSolenoid(15, PneumaticsModuleType.CTREPCM,
PneumaticConstants.kForwardChannel, PneumaticConstants.kReverseChannel);
// public static Compressor m_compressor = new
// Compressor(PneumaticsModuleType.CTREPCM);

Expand Down Expand Up @@ -61,8 +59,8 @@ private void configureBindings() {
// Set the default command for the drivetrain to drive using the joysticks
m_drivetrain.setDefaultCommand(

new RunCommand(() -> m_drivetrain.arcadeDrive(m_driverController.getLeftY() * (0.5 + speedUp),
m_driverController.getRightX() * (0.5 + speedUp)), m_drivetrain));
new RunCommand(() -> m_drivetrain.tankDrive(m_driverController.getLeftY() * (0.5 + speedUp),
m_driverController.getRightY() * (0.5 + speedUp)), m_drivetrain));

/*
* Extends piston when operator presses the "b" button Retracts piston when
Expand All @@ -71,8 +69,8 @@ private void configureBindings() {
* pushing and pulling air in the piston when the operator presses the "y"
* button
*/
m_operatorController.b().onTrue(PneumaticCommands.pistonExtend());
m_operatorController.a().onTrue(PneumaticCommands.pistonRetract());
m_operatorController.leftTrigger().onTrue(PneumaticCommands.pistonExtend());
m_operatorController.rightTrigger().onTrue(PneumaticCommands.pistonRetract());
m_operatorController.x().onTrue(PneumaticCommands.solenoidOff());
m_operatorController.y().onTrue(PneumaticCommands.solenoidToggle());
}
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/subsystems/Auto.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,16 @@
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.RobotContainer;
import frc.robot.commands.PneumaticCommands;

public class Auto {
public static Command getAuto(RobotContainer robot) {

return new SequentialCommandGroup( // basic auto to leave zone.
new WaitCommand(2), new InstantCommand(() -> RobotContainer.m_drivetrain.tankDrive(0.5, .5)),
new WaitCommand(2), new InstantCommand(() -> RobotContainer.m_drivetrain.tankDrive(0, 0)));
PneumaticCommands.pistonExtend(),
new WaitCommand(2), new InstantCommand(() -> RobotContainer.m_drivetrain.tankDrive(-0.5, -0.5)),
PneumaticCommands.pistonRetract(),
new WaitCommand(2), new InstantCommand(() -> RobotContainer.m_drivetrain.tankDrive(0, 0))
);
}
}
12 changes: 8 additions & 4 deletions src/main/java/frc/robot/subsystems/Pneumatics.java
Original file line number Diff line number Diff line change
@@ -1,26 +1,30 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import frc.robot.Constants.PneumaticConstants;
import frc.robot.RobotContainer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Pneumatics extends SubsystemBase {
// public Pneumatics() {
// RobotContainer.m_compressor.enableDigital();
// }
public DoubleSolenoid m_doubleSolenoid = new DoubleSolenoid(15, PneumaticsModuleType.CTREPCM,
PneumaticConstants.kForwardChannel, PneumaticConstants.kReverseChannel);
public void extendPiston() {
RobotContainer.m_doubleSolenoid.set(DoubleSolenoid.Value.kForward);
m_doubleSolenoid.set(DoubleSolenoid.Value.kForward);
}

public void retractPiston() {
RobotContainer.m_doubleSolenoid.set(DoubleSolenoid.Value.kReverse);
m_doubleSolenoid.set(DoubleSolenoid.Value.kReverse);
}

public void setSolenoidOff() {
RobotContainer.m_doubleSolenoid.set(DoubleSolenoid.Value.kOff);
m_doubleSolenoid.set(DoubleSolenoid.Value.kOff);
}

public void toggleSolenoid() {
RobotContainer.m_doubleSolenoid.toggle();
m_doubleSolenoid.toggle();
}
}

0 comments on commit e2a1098

Please sign in to comment.