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

Coral elevator #27

Merged
merged 4 commits into from
Jan 21, 2025
Merged
Show file tree
Hide file tree
Changes from 3 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
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,12 @@

public class RobotMap {

private RobotMap() {}
Einav-oss marked this conversation as resolved.
Show resolved Hide resolved
private RobotMap(){}

public static final int CORAL_ELEVATOR_UPPER_LIMIT_SWITCH = 1;
public static final int CORAL_ELEVATOR_LOWER_LIMIT_SWITCH = 2;
public static final int CORAL_ELEVATOR_PISTON_FORWARD_CHANNEL = 1;
public static final int CORAL_ELEVATOR_PISTON_REVERSE_CHANNEL = 1;


// add constants here
// public static final type NAME = value;
}
35 changes: 35 additions & 0 deletions src/main/java/frc/robot/commands/LowerCoralElevator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CoralElevator;

public class LowerCoralElevator extends Command {

private final CoralElevator coralElevator;

public LowerCoralElevator(CoralElevator coralElevator) {
this.coralElevator = coralElevator;
addRequirements(coralElevator);
}

@Override
public void initialize() {
coralElevator.lower();
}

@Override
public void execute() {
}

@Override
public void end(boolean interrupted) {

}

@Override
public boolean isFinished() {
return coralElevator.isLowered();
}


}
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/commands/RaiseCoralElevator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CoralElevator;

public class RaiseCoralElevator extends Command {

private final CoralElevator coralElevator;

public RaiseCoralElevator(CoralElevator coralElevator) {
this.coralElevator = coralElevator;

addRequirements(coralElevator);
}

@Override
public void initialize() {
coralElevator.raise();
}

@Override
public void execute() {
}

@Override
public void end(boolean interrupted) {
}

@Override
public boolean isFinished() {
return coralElevator.isRaised();
}

}
53 changes: 53 additions & 0 deletions src/main/java/frc/robot/subsystems/CoralElevator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.RobotMap;

public class CoralElevator extends SubsystemBase {

private final DoubleSolenoid piston1;
private final DoubleSolenoid piston2;
private final DigitalInput UpperLimitSwitch;
private final DigitalInput LowerLimitSwitch;

public CoralElevator() {
piston1 = new DoubleSolenoid(PneumaticsModuleType.REVPH, RobotMap.CORAL_ELEVATOR_PISTON_FORWARD_CHANNEL, RobotMap.CORAL_ELEVATOR_PISTON_REVERSE_CHANNEL);
piston2 = new DoubleSolenoid(PneumaticsModuleType.REVPH, RobotMap.CORAL_ELEVATOR_PISTON_FORWARD_CHANNEL, RobotMap.CORAL_ELEVATOR_PISTON_REVERSE_CHANNEL);
UpperLimitSwitch = new DigitalInput(RobotMap.CORAL_ELEVATOR_UPPER_LIMIT_SWITCH);
LowerLimitSwitch = new DigitalInput(RobotMap.CORAL_ELEVATOR_LOWER_LIMIT_SWITCH);
}

public boolean isRaised() {
return !UpperLimitSwitch.get();
}

public boolean isLowered() {
return !LowerLimitSwitch.get();
}

public void raise() {
piston1.set(DoubleSolenoid.Value.kForward);
piston2.set(DoubleSolenoid.Value.kForward);
}

public void lower() {
piston1.set(DoubleSolenoid.Value.kReverse);
piston2.set(DoubleSolenoid.Value.kReverse);
}

public void stop() {
piston1.set(DoubleSolenoid.Value.kOff);
piston2.set(DoubleSolenoid.Value.kOff);
}


@Override
public void periodic() {
SmartDashboard.putBoolean("Elevator Raised: " , isRaised());
SmartDashboard.putBoolean("Elevator Lowered: " , isLowered());
}
}