Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Climber #12

Merged
merged 16 commits into from
Feb 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,18 @@ public static final class IntakeConstants {
public static final class ShooterConstants {
public static final int kTopShooterMotorPort = 35;
public static final int kBottomShooterMotorPort = 20;
}

}
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 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
14 changes: 9 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,12 @@
package frc.robot;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
Expand All @@ -24,6 +21,7 @@
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.IOConstants;
import frc.robot.subsystems.ClimberSubsystem;
import frc.robot.commands.IntakeCommand;
import frc.robot.subsystems.DriveSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
Expand All @@ -39,7 +37,8 @@ public class RobotContainer {
// The robot's subsystems and commands are defined here
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
private final ShooterSubsystem m_shooterSubsystem = new ShooterSubsystem();
public final IntakeSubsystem m_intakeSubsystem = new IntakeSubsystem();
private final IntakeSubsystem m_intakeSubsystem = new IntakeSubsystem();
private final ClimberSubsystem m_climberSubsystem = new ClimberSubsystem();

private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);
private final XboxController m_operatorController = new XboxController(IOConstants.kOperatorControllerPort);
Expand Down Expand Up @@ -100,7 +99,7 @@ public RobotContainer() {
*/
private void configureBindings() {
new JoystickButton(m_driverController, Button.kStart.value)
.onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive));
.onTrue(new InstantCommand(() -> m_robotDrive.zeroHeading(), m_robotDrive));

// new JoystickButton(m_driverController, Button.kA.value).whileTrue(
// AutoBuilder.pathfindToPose(new Pose2d(2.8, 5.5, new Rotation2d()), new PathConstraints(
Expand All @@ -113,6 +112,11 @@ private void configureBindings() {
.onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(-0.75), m_shooterSubsystem))
.onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem));

new JoystickButton(m_operatorController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.forward(), m_robotDrive));
new JoystickButton(m_operatorController, Button.kB.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.reverse(), m_robotDrive));

new Trigger(() -> {
return m_driverController.getRightTriggerAxis() > 0.5;
}).whileTrue(new IntakeCommand(m_intakeSubsystem));
Expand Down
76 changes: 76 additions & 0 deletions src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;

import frc.robot.Constants.ClimberConstants;

import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward;
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kOff;
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;

public class ClimberSubsystem {

private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH,
ClimberConstants.leftForwardChannel, ClimberConstants.leftReverseChannel);
private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH,
ClimberConstants.rightForwardChannel, ClimberConstants.rightReverseChannel);

private final Compressor m_compressor = new Compressor(PneumaticsModuleType.REVPH);

private boolean enableCompressor = true;

public ClimberSubsystem() {
m_leftSolenoid.set(kOff);
m_rightSolenoid.set(kOff);
m_compressor.disable();
m_compressor.enableAnalog(ClimberConstants.minPressure, ClimberConstants.maxPressure);
}

// Runs once every tick (~20ms)
public void periodic() {
}

/**
* Sets the state of the solenoid to off
*/
public void off() {
m_leftSolenoid.set(kOff);
m_rightSolenoid.set(kOff);
}

/**
* Extends both arms
*/
public void forward() {
m_leftSolenoid.set(kForward);
m_rightSolenoid.set(kForward);
}

/**
* Retracts both arms
*/
public void reverse() {
m_leftSolenoid.set(kReverse);
m_rightSolenoid.set(kReverse);
}
/*
* Toggles the state of the climber
*/

public void toggle() {
ProgrammingSR marked this conversation as resolved.
Show resolved Hide resolved
m_leftSolenoid.toggle();
m_rightSolenoid.toggle();
}

// Toggles the state of the compressor (on/off)
public void toggleCompresor() {
enableCompressor = !enableCompressor;
if (enableCompressor) {
m_compressor.enableAnalog(ClimberConstants.minPressure, ClimberConstants.maxPressure);
} else {
m_compressor.disable();
}
}
}
Loading