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

27 Rename Arm to extension #37

Merged
merged 1 commit into from
Feb 14, 2025
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
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/commands/PrepClimbCommand.java
Original file line number Diff line number Diff line change
@@ -1,47 +1,47 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.constants.ArmConstants.ArmSetpoints;
import frc.robot.constants.ExtensionConstants.ExtensionSetpoints;
import frc.robot.constants.ShoulderConstants.ShoulderSetpoints;
import frc.robot.constants.WristConstants.WristSetPoints;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Extension;
import frc.robot.subsystems.Climb;
import frc.robot.subsystems.Shoulder;
import frc.robot.subsystems.Wrist;

public class PrepClimbCommand extends Command {
private Climb climb = Climb.getInstance();
private Arm arm = Arm.getInstance();
private Extension extension = Extension.getInstance();
private Shoulder shoulder = Shoulder.getInstance();
private Wrist wrist = Wrist.getInstance();

public PrepClimbCommand() {
addRequirements(climb, arm, shoulder, wrist);
addRequirements(climb, extension, shoulder, wrist);
}

@Override
public void initialize() {
arm.enable();
extension.enable();
shoulder.enable();
wrist.enable();
}

@Override
public void execute() {
arm.setSetpoint(ArmSetpoints.Climb);
extension.setSetpoint(ExtensionSetpoints.Climb);
wrist.setSetpoint(WristSetPoints.Climb);
shoulder.setSetpoint(ShoulderSetpoints.Climb);
climb.runClimbDown();
}

@Override
public boolean isFinished() {
return arm.onTarget() && wrist.onTarget() && shoulder.onTarget();
return extension.onTarget() && wrist.onTarget() && shoulder.onTarget();
}

@Override
public void end(boolean interrupted) {
arm.disable();
extension.disable();
shoulder.disable();
wrist.disable();
climb.stopClimb();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,38 +3,38 @@
import com.revrobotics.spark.SparkClosedLoopController.ArbFFUnits;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.constants.ArmConstants.ArmSetpoints;
import frc.robot.constants.ExtensionConstants.ExtensionSetpoints;
import frc.robot.constants.ShoulderConstants.ShoulderSetpoints;
import frc.robot.constants.WristConstants.WristSetPoints;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Extension;
import frc.robot.subsystems.Shoulder;
import frc.robot.subsystems.Wrist;

public class SetAcquisitionPositionCommand extends Command {

private Shoulder shoulder = Shoulder.getInstance();
private Wrist wrist = Wrist.getInstance();
private Arm arm = Arm.getInstance();
private Extension extension = Extension.getInstance();
private AcquisitionPositionSetpoint acquisitionPositionSetpoint;

public enum AcquisitionPositionSetpoint {

L1Coral(ShoulderSetpoints.L1Coral, WristSetPoints.L1Coral, ArmSetpoints.L1Coral),
L2Coral(ShoulderSetpoints.L2Coral, WristSetPoints.L2Coral, ArmSetpoints.L2Coral),
L3Coral(ShoulderSetpoints.L3Coral, WristSetPoints.L3Coral, ArmSetpoints.L3Coral),
L4Coral(ShoulderSetpoints.L4Coral, WristSetPoints.L4Coral, ArmSetpoints.L4Coral),
L23Algae(ShoulderSetpoints.L23Algae, WristSetPoints.L23Algae, ArmSetpoints.L23Algae),
L34Algae(ShoulderSetpoints.L34Algae, WristSetPoints.L34Algae, ArmSetpoints.L34Algae),
Processor(ShoulderSetpoints.Processor, WristSetPoints.Processor, ArmSetpoints.Processor),
FeederStation(ShoulderSetpoints.FeederStation, WristSetPoints.FeederStation, ArmSetpoints.FeederStation),
Storage(ShoulderSetpoints.Storage, WristSetPoints.Storage, ArmSetpoints.Storage);
L1Coral(ShoulderSetpoints.L1Coral, WristSetPoints.L1Coral, ExtensionSetpoints.L1Coral),
L2Coral(ShoulderSetpoints.L2Coral, WristSetPoints.L2Coral, ExtensionSetpoints.L2Coral),
L3Coral(ShoulderSetpoints.L3Coral, WristSetPoints.L3Coral, ExtensionSetpoints.L3Coral),
L4Coral(ShoulderSetpoints.L4Coral, WristSetPoints.L4Coral, ExtensionSetpoints.L4Coral),
L23Algae(ShoulderSetpoints.L23Algae, WristSetPoints.L23Algae, ExtensionSetpoints.L23Algae),
L34Algae(ShoulderSetpoints.L34Algae, WristSetPoints.L34Algae, ExtensionSetpoints.L34Algae),
Processor(ShoulderSetpoints.Processor, WristSetPoints.Processor, ExtensionSetpoints.Processor),
FeederStation(ShoulderSetpoints.FeederStation, WristSetPoints.FeederStation, ExtensionSetpoints.FeederStation),
Storage(ShoulderSetpoints.Storage, WristSetPoints.Storage, ExtensionSetpoints.Storage);

private ShoulderSetpoints shoulderSetpoint;
private WristSetPoints wristSetPoint;
private ArmSetpoints armSetpoint;
private ExtensionSetpoints armSetpoint;

private AcquisitionPositionSetpoint(ShoulderSetpoints shoulderSetpoint, WristSetPoints wristSetPoint,
ArmSetpoints armSetpoint) {
ExtensionSetpoints armSetpoint) {
this.shoulderSetpoint = shoulderSetpoint;
this.wristSetPoint = wristSetPoint;
this.armSetpoint = armSetpoint;
Expand All @@ -48,32 +48,32 @@ public WristSetPoints getWristSetpoint() {
return this.wristSetPoint;
}

public ArmSetpoints getArmSetpoint() {
public ExtensionSetpoints getArmSetpoint() {
return this.armSetpoint;
}
}

public SetAcquisitionPositionCommand(AcquisitionPositionSetpoint acquisitionPositionSetpoint) {
addRequirements(shoulder, wrist, arm);
addRequirements(shoulder, wrist, extension);
this.acquisitionPositionSetpoint = acquisitionPositionSetpoint;
}

public void initialize() {
wrist.enable();
shoulder.enable();
arm.enable();
extension.enable();
shoulder.setSetpoint(this.acquisitionPositionSetpoint.getShoulderSetpoint());
wrist.setSetpoint(this.acquisitionPositionSetpoint.getWristSetpoint());
arm.setSetpoint(this.acquisitionPositionSetpoint.getArmSetpoint());
extension.setSetpoint(this.acquisitionPositionSetpoint.getArmSetpoint());
}

public boolean isFinished() {
return wrist.onTarget() && shoulder.onTarget() && arm.onTarget();
return wrist.onTarget() && shoulder.onTarget() && extension.onTarget();
}

public void end(boolean interrupted) {
wrist.disable();
shoulder.disable();
arm.disable();
extension.disable();
}
}
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
package frc.robot.constants;

public class ArmConstants {
public static final int kArmMotorPort = 0;
public static final int kArmLaserPort = 0;
public class ExtensionConstants {
public static final int kExtensionMotorPort = 0;
public static final int kExtensionLaserPort = 0;

public static final double kMinArmPower = 0.0;
public static final double kMaxArmPower = 0.0;
public static final double kArmMaxExtension = 0.0;
public static final double kMinExtensionPower = 0.0;
public static final double kMaxExtensionPower = 0.0;
public static final double kExtensionMaximum = 0.0;

public static final double kTolerance = 0.0;
public static final double kEncoderConversion = 0.0;
public static final double kP = 0.0;
public static final double kI = 0.0;
public static final double kD = 0.0;

public enum ArmSetpoints {
public enum ExtensionSetpoints {
L1Coral(0.0),
L2Coral(0.0),
L3Coral(0.0),
Expand All @@ -29,7 +29,7 @@ public enum ArmSetpoints {

public final double position;

ArmSetpoints(double position) {
ExtensionSetpoints(double position) {
this.position = position;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,56 +13,58 @@
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ArmConstants;
import frc.robot.constants.ExtensionConstants;
import frc.robot.constants.NeoMotorConstants;
import frc.robot.constants.ArmConstants.ArmSetpoints;

public class Arm extends SubsystemBase {
private SparkFlex armMotor = new SparkFlex(ArmConstants.kArmMotorPort, MotorType.kBrushless);
private PIDController armController = new PIDController(ArmConstants.kP, ArmConstants.kI, ArmConstants.kD);
private SparkLimitSwitch limitSwitch = armMotor.getReverseLimitSwitch();
private LaserCan laser = new LaserCan(ArmConstants.kArmLaserPort);
private static Arm instance;
import frc.robot.constants.ExtensionConstants.ExtensionSetpoints;

public class Extension extends SubsystemBase {
private SparkFlex extensionMotor = new SparkFlex(ExtensionConstants.kExtensionMotorPort, MotorType.kBrushless);
private PIDController extensionController = new PIDController(ExtensionConstants.kP, ExtensionConstants.kI,
ExtensionConstants.kD);
private SparkLimitSwitch limitSwitch = extensionMotor.getReverseLimitSwitch();
private LaserCan laser = new LaserCan(ExtensionConstants.kExtensionLaserPort);
private static Extension instance;
private boolean enabled;

/**
* Creates an instance of the Arm subsystem if it does not exist.
*
* @return An instance of the arm subsystem
*/
public static Arm getInstance() {
public static Extension getInstance() {
if (instance == null) {
instance = new Arm();
instance = new Extension();
}
return instance;
}

private Arm() {
SparkFlexConfig armConfig = new SparkFlexConfig();
armConfig.idleMode(IdleMode.kBrake)
private Extension() {
SparkFlexConfig extensionConfig = new SparkFlexConfig();
extensionConfig.idleMode(IdleMode.kBrake)
.smartCurrentLimit(NeoMotorConstants.kMaxVortexCurrent);

armMotor.configure(armConfig, ResetMode.kResetSafeParameters,
extensionMotor.configure(extensionConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);

armConfig.limitSwitch
extensionConfig.limitSwitch
.reverseLimitSwitchType(Type.kNormallyOpen)
.reverseLimitSwitchEnabled(true);

armController.setTolerance(ArmConstants.kTolerance);
armController.disableContinuousInput();
extensionController.setTolerance(ExtensionConstants.kTolerance);
extensionController.disableContinuousInput();
}

@Override
public void periodic() {
if (enabled) {
useOutput(armController.calculate(getPosition()));
useOutput(extensionController.calculate(getPosition()));
}
}

protected void useOutput(double output) {
double power = MathUtil.clamp(output, -ArmConstants.kMaxArmPower, ArmConstants.kMaxArmPower);
armMotor.set(power);
double power = MathUtil.clamp(output, -ExtensionConstants.kMaxExtensionPower,
ExtensionConstants.kMaxExtensionPower);
extensionMotor.set(power);
}

/**
Expand All @@ -84,7 +86,7 @@ public double getPosition() {
* @return The current setpoint
*/
public double getSetpoint() {
return armController.getSetpoint();
return extensionController.getSetpoint();
}

/**
Expand All @@ -93,7 +95,7 @@ public double getSetpoint() {
* @return boolean whether or not the PID controller is at setpoint
*/
public boolean onTarget() {
return armController.atSetpoint();
return extensionController.atSetpoint();
}

/**
Expand All @@ -110,7 +112,7 @@ public boolean isLimitSwitchPressed() {
*
* @param setpoint the setpoint for the subsystem
*/
public void setSetpoint(ArmSetpoints setpoint) {
public void setSetpoint(ExtensionSetpoints setpoint) {
setSetpoint(setpoint.position);
}

Expand All @@ -120,8 +122,8 @@ public void setSetpoint(ArmSetpoints setpoint) {
* @param setpoint the setpoint for the subsystem
*/
private final void setSetpoint(double setpoint) {
setpoint = MathUtil.clamp(setpoint, 0, ArmConstants.kArmMaxExtension);
armController.setSetpoint(setpoint);
setpoint = MathUtil.clamp(setpoint, 0, ExtensionConstants.kExtensionMaximum);
extensionController.setSetpoint(setpoint);
}

/**
Expand All @@ -130,7 +132,7 @@ private final void setSetpoint(double setpoint) {
* @param P the P to set to the PID controller
*/
public void setP(double P) {
armController.setP(P);
extensionController.setP(P);
}

/**
Expand All @@ -139,7 +141,7 @@ public void setP(double P) {
* @param I the I to set to the PID controller
*/
public void setI(double I) {
armController.setP(I);
extensionController.setP(I);
}

/**
Expand All @@ -148,13 +150,13 @@ public void setI(double I) {
* @param D the D to set to the PID controller
*/
public void setD(double D) {
armController.setP(D);
extensionController.setP(D);
}

/** Enables the PID control. Resets the controller. */
public void enable() {
enabled = true;
armController.reset();
extensionController.reset();
}

/** Disables the PID control. Sets output to zero. */
Expand Down