Skip to content

Commit

Permalink
Merge pull request #21 from LakotaRobotics1038/10-acquire-all-sides-c…
Browse files Browse the repository at this point in the history
…ommand-skeleton

Acquire all sides command skeleton complete
  • Loading branch information
reediculous456 authored Jan 16, 2024
2 parents 9872d4a + 6563581 commit 48d6f71
Show file tree
Hide file tree
Showing 3 changed files with 47 additions and 21 deletions.
31 changes: 31 additions & 0 deletions src/main/java/frc/robot/commands/AcquireCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
package frc.robot.commands;

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

public class AcquireCommand extends Command {
private static Acquisition acquisition = Acquisition.getInstance();

private double speed;

public AcquireCommand(double speed) {
addRequirements(acquisition);
this.speed = speed;
}

@Override
public void execute() {
acquisition.acquire(speed);
}

@Override
public boolean isFinished() {
// TODO: update with sensors
return false;
}

@Override
public void end(boolean interrupted) {
acquisition.stop();
}
}
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/constants/AcquisitionConstants.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
package frc.robot.constants;

public class AcquisitionConstants {
public static final int rearMotorPort = -1;
public static final int frontMotorPort = -1;
public static final int motorPort = -1;

public static final double motorSpeed = 0.0;
public static final double reverseMotorSpeed = 0.0;
public static final double maxMotorSpeed = 1;
public static final double minMotorSpeed = -1;
}
31 changes: 12 additions & 19 deletions src/main/java/frc/robot/subsystems/Acquisition.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,25 +4,21 @@
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.AcquisitionConstants;

public class Acquisition extends SubsystemBase {
private static Acquisition instance;

private static CANSparkMax rearMotor = new CANSparkMax(AcquisitionConstants.frontMotorPort, MotorType.kBrushless);
private static CANSparkMax frontMotor = new CANSparkMax(AcquisitionConstants.frontMotorPort, MotorType.kBrushless);
private static CANSparkMax driveMotor = new CANSparkMax(AcquisitionConstants.motorPort, MotorType.kBrushless);

private Acquisition() {
rearMotor.restoreFactoryDefaults();
frontMotor.restoreFactoryDefaults();
driveMotor.restoreFactoryDefaults();

rearMotor.setIdleMode(IdleMode.kBrake);
driveMotor.setIdleMode(IdleMode.kBrake);

rearMotor.follow(frontMotor);

rearMotor.burnFlash();
frontMotor.burnFlash();
driveMotor.burnFlash();
}

public static Acquisition getInstance() {
Expand All @@ -32,19 +28,16 @@ public static Acquisition getInstance() {
return instance;
}

public void runRear() {
rearMotor.set(AcquisitionConstants.motorSpeed);
}

public void runFront() {
frontMotor.set(AcquisitionConstants.motorSpeed);
public void acquire(double speed) {
speed = MathUtil.clamp(speed, AcquisitionConstants.minMotorSpeed, AcquisitionConstants.maxMotorSpeed);
driveMotor.set(speed);
}

public void stopRear() {
rearMotor.stopMotor();
public void dispose() {
driveMotor.set(-AcquisitionConstants.motorSpeed);
}

public void stopFront() {
frontMotor.stopMotor();
public void stop() {
driveMotor.stopMotor();
}
}

0 comments on commit 48d6f71

Please sign in to comment.