2024-01-19 21:24:11 -07:00
|
|
|
// Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
// the WPILib BSD license file in the root directory of this project.
|
|
|
|
|
|
|
|
|
|
package frc4388.robot.subsystems;
|
|
|
|
|
|
2024-02-10 15:48:00 -07:00
|
|
|
import java.util.function.BooleanSupplier;
|
|
|
|
|
|
2024-01-19 21:24:11 -07:00
|
|
|
import com.revrobotics.CANSparkMax;
|
|
|
|
|
import com.revrobotics.SparkLimitSwitch;
|
2024-02-07 18:53:57 -07:00
|
|
|
import com.revrobotics.SparkPIDController;
|
2024-02-06 19:24:32 -07:00
|
|
|
import com.revrobotics.RelativeEncoder;
|
2024-01-19 21:24:11 -07:00
|
|
|
import edu.wpi.first.wpilibj.CAN;
|
|
|
|
|
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
2024-02-09 22:01:27 -07:00
|
|
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
2024-01-19 21:24:11 -07:00
|
|
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
2024-02-07 18:53:57 -07:00
|
|
|
import frc4388.robot.Constants;
|
2024-01-20 10:10:17 -07:00
|
|
|
import frc4388.robot.Constants.IntakeConstants;
|
2024-02-07 18:53:57 -07:00
|
|
|
import frc4388.robot.commands.PID;
|
|
|
|
|
import frc4388.utility.Gains;
|
2024-01-19 21:24:11 -07:00
|
|
|
|
|
|
|
|
public class Intake extends SubsystemBase {
|
2024-01-26 20:56:02 -07:00
|
|
|
|
2024-01-22 18:04:12 -07:00
|
|
|
private CANSparkMax intakeMotor;
|
|
|
|
|
private CANSparkMax pivot;
|
2024-02-07 18:53:57 -07:00
|
|
|
private SparkPIDController m_spedController;
|
|
|
|
|
private static Gains armGains = IntakeConstants.ArmPID.INTAKE_GAINS;
|
|
|
|
|
private SparkLimitSwitch forwardLimit;
|
|
|
|
|
private SparkLimitSwitch reverseLimit;
|
2024-02-10 13:11:30 -07:00
|
|
|
private SparkLimitSwitch intakeforwardLimit;
|
|
|
|
|
private SparkLimitSwitch intakereverseLimit;
|
|
|
|
|
|
|
|
|
|
private Shooter shooter;
|
|
|
|
|
|
2024-02-13 20:01:12 -07:00
|
|
|
private BooleanSupplier sup = () -> true;
|
|
|
|
|
private BooleanSupplier dup = () -> false;
|
|
|
|
|
|
|
|
|
|
|
2024-02-10 13:11:30 -07:00
|
|
|
|
2024-02-06 19:24:32 -07:00
|
|
|
|
2024-01-26 20:56:02 -07:00
|
|
|
/** Creates a new Intake. */
|
2024-01-22 18:04:12 -07:00
|
|
|
public Intake(CANSparkMax intakeMotor, CANSparkMax pivot) {
|
2024-01-19 21:24:11 -07:00
|
|
|
this.intakeMotor = intakeMotor;
|
2024-01-22 17:43:40 -07:00
|
|
|
this.pivot = pivot;
|
2024-02-07 18:53:57 -07:00
|
|
|
|
|
|
|
|
pivot.restoreFactoryDefaults();
|
2024-02-09 22:01:27 -07:00
|
|
|
//pivot.setInverted(true);
|
2024-02-07 18:53:57 -07:00
|
|
|
|
2024-02-09 22:01:27 -07:00
|
|
|
forwardLimit = pivot.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen);
|
|
|
|
|
reverseLimit = pivot.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen);
|
2024-02-07 18:53:57 -07:00
|
|
|
forwardLimit.enableLimitSwitch(true);
|
|
|
|
|
reverseLimit.enableLimitSwitch(true);
|
2024-02-10 13:11:30 -07:00
|
|
|
|
|
|
|
|
intakeMotor.restoreFactoryDefaults();
|
|
|
|
|
|
2024-02-07 18:53:57 -07:00
|
|
|
|
2024-02-10 13:11:30 -07:00
|
|
|
intakeforwardLimit = intakeMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen);
|
|
|
|
|
intakereverseLimit = intakeMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen);
|
|
|
|
|
intakeforwardLimit.enableLimitSwitch(true);
|
|
|
|
|
intakereverseLimit.enableLimitSwitch(false);
|
2024-02-07 18:53:57 -07:00
|
|
|
|
|
|
|
|
//Arm PID
|
2024-02-09 22:01:27 -07:00
|
|
|
m_spedController = pivot.getPIDController();
|
2024-02-07 18:53:57 -07:00
|
|
|
m_spedController.setP(armGains.kP);
|
|
|
|
|
m_spedController.setI(armGains.kI);
|
|
|
|
|
m_spedController.setD(armGains.kD);
|
2024-01-19 21:24:11 -07:00
|
|
|
}
|
|
|
|
|
|
2024-01-26 18:10:29 -07:00
|
|
|
//hanoff
|
2024-01-19 21:24:11 -07:00
|
|
|
public void spinIntakeMotor() {
|
2024-01-20 10:10:17 -07:00
|
|
|
intakeMotor.set(IntakeConstants.INTAKE_SPEED);
|
2024-01-19 21:24:11 -07:00
|
|
|
}
|
|
|
|
|
|
2024-01-26 18:10:29 -07:00
|
|
|
//Rotate robot in for handoff
|
|
|
|
|
public void rotateArmIn() {
|
2024-02-09 22:01:27 -07:00
|
|
|
//pivot.set(IntakeConstants.PIVOT_SPEED);
|
2024-01-26 18:10:29 -07:00
|
|
|
pivot.set(IntakeConstants.PIVOT_SPEED);
|
2024-01-22 17:43:40 -07:00
|
|
|
}
|
|
|
|
|
|
2024-01-26 18:10:29 -07:00
|
|
|
//Rotates robot out for intake
|
|
|
|
|
public void rotateArmOut() {
|
2024-01-26 20:56:02 -07:00
|
|
|
pivot.set(-IntakeConstants.PIVOT_SPEED);
|
|
|
|
|
|
|
|
|
|
}
|
2024-01-26 18:10:29 -07:00
|
|
|
|
2024-02-09 22:01:27 -07:00
|
|
|
public void pidIn() {
|
2024-02-10 15:48:00 -07:00
|
|
|
m_spedController.setReference(2.5, CANSparkMax.ControlType.kPosition);
|
2024-02-09 22:01:27 -07:00
|
|
|
//SmartDashboard.putNumber("Velocity Output", pivot.getEncoder().getVelocity());
|
|
|
|
|
}
|
|
|
|
|
|
2024-02-10 15:48:00 -07:00
|
|
|
public void limitNote() {
|
|
|
|
|
if (intakeforwardLimit.isPressed()) {
|
|
|
|
|
rotateArmIn2();
|
|
|
|
|
} else {
|
|
|
|
|
spinIntakeMotor();
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2024-02-09 22:01:27 -07:00
|
|
|
public void pidOut() {
|
2024-02-10 15:48:00 -07:00
|
|
|
m_spedController.setReference(-53, CANSparkMax.ControlType.kPosition);
|
|
|
|
|
}
|
2024-02-09 22:01:27 -07:00
|
|
|
|
2024-02-10 15:48:00 -07:00
|
|
|
public void rotateArmOut2() {
|
|
|
|
|
if(reverseLimit.isPressed()){
|
|
|
|
|
stopArmMotor();
|
|
|
|
|
} else {
|
|
|
|
|
pidOut();
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void rotateArmIn2() {
|
|
|
|
|
if(forwardLimit.isPressed()){
|
|
|
|
|
stopArmMotor();
|
|
|
|
|
} else {
|
|
|
|
|
pidIn();
|
|
|
|
|
}
|
2024-02-09 22:01:27 -07:00
|
|
|
}
|
2024-02-10 13:11:30 -07:00
|
|
|
|
2024-01-26 20:56:02 -07:00
|
|
|
public void handoff() {
|
2024-02-10 13:11:30 -07:00
|
|
|
intakeMotor.set(-IntakeConstants.INTAKE_OUT_SPEED);
|
2024-01-26 18:10:29 -07:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void stopIntakeMotors() {
|
|
|
|
|
intakeMotor.set(0);
|
2024-01-22 17:43:40 -07:00
|
|
|
}
|
2024-02-09 22:01:27 -07:00
|
|
|
|
|
|
|
|
public void stopArmMotor() {
|
|
|
|
|
pivot.set(0);
|
|
|
|
|
}
|
|
|
|
|
|
2024-02-06 19:24:32 -07:00
|
|
|
public RelativeEncoder getEncoder() {
|
|
|
|
|
return pivot.getEncoder();
|
|
|
|
|
}
|
2024-02-13 20:01:12 -07:00
|
|
|
|
|
|
|
|
public boolean getForwardLimitSwitchState() {
|
|
|
|
|
return forwardLimit.isPressed();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public boolean getReverseLimitSwitchState() {
|
|
|
|
|
return reverseLimit.isPressed();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public boolean getIntakeLimitSwtichState() {
|
|
|
|
|
return intakeforwardLimit.isPressed();
|
|
|
|
|
}
|
|
|
|
|
|
2024-02-06 19:24:32 -07:00
|
|
|
public void setVoltage(double voltage) {
|
|
|
|
|
pivot.setVoltage(voltage);
|
|
|
|
|
}
|
2024-02-09 22:01:27 -07:00
|
|
|
|
|
|
|
|
public double getVelocity() {
|
|
|
|
|
return pivot.getEncoder().getVelocity();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void resetPostion() {
|
|
|
|
|
pivot.getEncoder().setPosition(0);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void resetPosition1() {
|
2024-02-13 20:01:12 -07:00
|
|
|
if(forwardLimit.isPressed()) {
|
2024-02-09 22:01:27 -07:00
|
|
|
resetPostion();
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public double getPos() {
|
|
|
|
|
return pivot.getEncoder().getPosition();
|
|
|
|
|
}
|
|
|
|
|
|
2024-01-22 17:43:40 -07:00
|
|
|
public void rotateArm() {
|
2024-02-06 19:24:32 -07:00
|
|
|
|
2024-01-22 17:43:40 -07:00
|
|
|
}
|
|
|
|
|
|
2024-02-10 15:48:00 -07:00
|
|
|
public BooleanSupplier getArmFowardLimitState() {
|
2024-02-13 20:01:12 -07:00
|
|
|
if(forwardLimit.isPressed()) {
|
|
|
|
|
return sup;
|
|
|
|
|
} else {
|
|
|
|
|
return dup;
|
|
|
|
|
}
|
2024-02-10 15:48:00 -07:00
|
|
|
}
|
|
|
|
|
|
2024-01-19 21:24:11 -07:00
|
|
|
@Override
|
|
|
|
|
public void periodic() {
|
|
|
|
|
// This method will be called once per scheduler run
|
2024-02-09 22:01:27 -07:00
|
|
|
SmartDashboard.putNumber("Vel Output", getVelocity());
|
|
|
|
|
SmartDashboard.putNumber("Position", getPos());
|
|
|
|
|
resetPosition1();
|
2024-01-19 21:24:11 -07:00
|
|
|
}
|
|
|
|
|
}
|