Skip to content

Commit

Permalink
arm subsystem
Browse files Browse the repository at this point in the history
  • Loading branch information
s-aditya-k committed Jan 16, 2024
1 parent f9aa9a8 commit 75b1534
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 6 deletions.
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,12 @@ public final class Constants {

public static final class HardwarePorts {
// motors (predicted) IDs not fixed
// shooter ports should be correct, climb IDs still predicted
public static final int shooterLeaderM = 21;
public static final int shooterFollowerM = 22;
public static final int climbLeaderMotor = 3;
public static final int climbFollowerMotor = 4;

// TODO actually set correct port IDs at some point
public static final int shooterLeaderM = 21; // should be correct
public static final int shooterFollowerM = 22; // should be correct
public static final int climbLeaderMotor = 3; // predicted
public static final int climbFollowerMotor = 4; //predicted
public static final int armMotor = -1; // !! invalid !! needs to be set
}

public static final double FIELD_WIDTH_METERS = 8.21055;
Expand Down
37 changes: 37 additions & 0 deletions src/main/java/frc/robot/subsystems/ArmSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
package frc.robot.subsystems;

import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class ArmSubsystem extends SubsystemBase {
private static ArmSubsystem instance;

public static ArmSubsystem getInstance() {
if (instance == null) {
instance = new ArmSubsystem();
}
return instance;
}

private TalonFX motor;

private ArmSubsystem() {
motor = new TalonFX(Constants.HardwarePorts.armMotor);
}

public enum ArmState {
FLOOR(0.0),
AMP(80.0), // TODO set to some real value, this is totally random
SPEAKER(120.0); // TODO set to some real value, this is totally random
final double position;

ArmState(double position) {
this.position = position;
}
}

public void setState(ArmState state) {
motor.setPosition(state.position);
}
}

0 comments on commit 75b1534

Please sign in to comment.