Fixing indentation and formatting
This commit is contained in:
parent
236ee989ff
commit
b7a3e3d2f8
@ -7,15 +7,20 @@ import com.revrobotics.CANSparkLowLevel.MotorType;
|
|||||||
|
|
||||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||||
import edu.wpi.first.math.controller.PIDController;
|
import edu.wpi.first.math.controller.PIDController;
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
import frc.robot.constants.IntakeConstants;
|
import frc.robot.constants.IntakeConstants;
|
||||||
|
|
||||||
public class Intake extends SubsystemBase{
|
public class Intake extends SubsystemBase{
|
||||||
private PIDController intakeAnglePID;
|
private PIDController intakeAnglePID;
|
||||||
|
|
||||||
private CANSparkMax intakeRoller;
|
private CANSparkMax intakeRoller;
|
||||||
private CANSparkMax intakePivot;
|
private CANSparkMax intakePivot;
|
||||||
|
|
||||||
private RelativeEncoder intakeEncoder;
|
private RelativeEncoder intakeEncoder;
|
||||||
|
|
||||||
private ArmFeedforward intakeFeedForward;
|
private ArmFeedforward intakeFeedForward;
|
||||||
|
|
||||||
public Intake(){
|
public Intake(){
|
||||||
intakeRoller = new CANSparkMax(IntakeConstants.kIntakeRollerID, MotorType.kBrushless);
|
intakeRoller = new CANSparkMax(IntakeConstants.kIntakeRollerID, MotorType.kBrushless);
|
||||||
|
|
||||||
@ -29,25 +34,56 @@ public class Intake extends SubsystemBase{
|
|||||||
intakeEncoder = intakePivot.getEncoder();
|
intakeEncoder = intakePivot.getEncoder();
|
||||||
intakeEncoder.setPosition(IntakeConstants.kStartingAngle);
|
intakeEncoder.setPosition(IntakeConstants.kStartingAngle);
|
||||||
intakeEncoder.setPositionConversionFactor(IntakeConstants.kIntakePivotConversionFactor);
|
intakeEncoder.setPositionConversionFactor(IntakeConstants.kIntakePivotConversionFactor);
|
||||||
|
|
||||||
intakeAnglePID = new PIDController(IntakeConstants.kPIntake, IntakeConstants.kIIntake, IntakeConstants.kDIntake);
|
intakeAnglePID = new PIDController(IntakeConstants.kPIntake, IntakeConstants.kIIntake, IntakeConstants.kDIntake);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public void intakeDown(){
|
public Command intakeDownCommand() {
|
||||||
|
return run(() -> {
|
||||||
intakeRoller.set(1.0);
|
intakeRoller.set(1.0);
|
||||||
|
|
||||||
intakePivot.setVoltage(intakeAnglePID.calculate(intakeEncoder.getPosition(), IntakeConstants.kDownAngle) + intakeFeedForward.calculate(IntakeConstants.kDownAngle, intakeEncoder.getVelocity()));
|
intakePivot.setVoltage(
|
||||||
|
intakeAnglePID.calculate(
|
||||||
|
intakeEncoder.getPosition(),
|
||||||
|
IntakeConstants.kDownAngle
|
||||||
|
) + intakeFeedForward.calculate(
|
||||||
|
IntakeConstants.kDownAngle,
|
||||||
|
intakeEncoder.getVelocity()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
public void climbingState(){
|
public Command climbingStateCommand() {
|
||||||
|
return run(() -> {
|
||||||
intakeRoller.set(0.0);
|
intakeRoller.set(0.0);
|
||||||
|
|
||||||
intakePivot.setVoltage(intakeAnglePID.calculate(intakeEncoder.getPosition(), IntakeConstants.kDownAngle) + intakeFeedForward.calculate(IntakeConstants.kDownAngle, intakeEncoder.getVelocity()));
|
intakePivot.setVoltage(
|
||||||
|
intakeAnglePID.calculate(
|
||||||
|
intakeEncoder.getPosition(),
|
||||||
|
IntakeConstants.kDownAngle
|
||||||
|
) + intakeFeedForward.calculate(
|
||||||
|
IntakeConstants.kDownAngle,
|
||||||
|
intakeEncoder.getVelocity()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
public void intakeUp(){
|
public Command intakeUpCommand() {
|
||||||
|
return run(() -> {
|
||||||
intakeRoller.set(0.0);
|
intakeRoller.set(0.0);
|
||||||
|
|
||||||
intakePivot.setVoltage(intakeAnglePID.calculate(intakeEncoder.getPosition(), IntakeConstants.kUpAngle) + intakeFeedForward.calculate(IntakeConstants.kUpAngle, intakeEncoder.getVelocity()));
|
intakePivot.setVoltage(
|
||||||
|
intakeAnglePID.calculate(
|
||||||
|
intakeEncoder.getPosition(),
|
||||||
|
IntakeConstants.kUpAngle
|
||||||
|
) + intakeFeedForward.calculate(
|
||||||
|
IntakeConstants.kUpAngle,
|
||||||
|
intakeEncoder.getVelocity()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
});
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user