mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 00:38:05 -06:00
Merge branch 'full-robot-test' into Intake
This commit is contained in:
@@ -16,19 +16,21 @@ import com.revrobotics.CANSparkMax.SoftLimitDirection;
|
||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
// import frc4388.robot.Constants.ShooterConstants;
|
||||
|
||||
|
||||
import frc4388.robot.Constants.ShooterConstants;
|
||||
import frc4388.utility.Gains;
|
||||
|
||||
public class Hood extends SubsystemBase {
|
||||
// public BoomBoom m_shooterSubsystem;
|
||||
public BoomBoom m_shooterSubsystem;
|
||||
|
||||
public CANSparkMax m_angleAdjusterMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
|
||||
public SparkMaxLimitSwitch m_hoodUpLimitSwitch;
|
||||
public SparkMaxLimitSwitch m_hoodDownLimitSwitch;
|
||||
// public static Gains m_angleAdjusterGains = ShooterConstants.SHOOTER_ANGLE_GAINS;
|
||||
public RelativeEncoder m_angleEncoder;
|
||||
public CANSparkMax m_angleAdjustMotor;
|
||||
public SparkMaxPIDController m_angleAdjusterPIDController;
|
||||
public static Gains m_angleAdjusterGains = ShooterConstants.SHOOTER_ANGLE_GAINS;
|
||||
public RelativeEncoder m_angleEncoder = m_angleAdjusterMotor.getEncoder();
|
||||
|
||||
public SparkMaxPIDController m_angleAdjusterPIDController = m_angleAdjusterMotor.getPIDController();
|
||||
|
||||
|
||||
public boolean m_isHoodReady = false;
|
||||
@@ -37,15 +39,17 @@ public double m_fireAngle;
|
||||
|
||||
|
||||
/** Creates a new Hood. */
|
||||
public Hood(CANSparkMax angleAdjustMotor) {
|
||||
m_angleAdjustMotor = angleAdjustMotor;
|
||||
m_angleAdjustMotor.setIdleMode(IdleMode.kBrake);
|
||||
m_angleEncoder= m_angleAdjustMotor.getEncoder();
|
||||
m_angleAdjusterPIDController = m_angleAdjustMotor.getPIDController();
|
||||
m_hoodUpLimitSwitch = m_angleAdjustMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
m_hoodDownLimitSwitch = m_angleAdjustMotor.getReverseLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
public Hood() {
|
||||
m_angleAdjusterMotor.setIdleMode(IdleMode.kBrake);
|
||||
|
||||
m_hoodUpLimitSwitch = m_angleAdjusterMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
m_hoodDownLimitSwitch = m_angleAdjusterMotor.getReverseLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
m_hoodUpLimitSwitch.enableLimitSwitch(true);
|
||||
m_hoodDownLimitSwitch.enableLimitSwitch(true);
|
||||
|
||||
m_angleAdjusterMotor.setSoftLimit(SoftLimitDirection.kForward, ShooterConstants.HOOD_FORWARD_LIMIT);
|
||||
m_angleAdjusterMotor.setSoftLimit(SoftLimitDirection.kReverse, ShooterConstants.HOOD_REVERSE_LIMIT);
|
||||
setHoodSoftLimits(true);
|
||||
}
|
||||
|
||||
|
||||
@@ -53,44 +57,43 @@ public double m_fireAngle;
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
// public void runAngleAdjustPID(double targetAngle)
|
||||
// {
|
||||
// //Set PID Coefficients
|
||||
// m_angleAdjusterPIDController.setP(m_angleAdjusterGains.m_kP);
|
||||
// m_angleAdjusterPIDController.setI(m_angleAdjusterGains.m_kI);
|
||||
// m_angleAdjusterPIDController.setD(m_angleAdjusterGains.m_kD);
|
||||
// m_angleAdjusterPIDController.setIZone(m_angleAdjusterGains.m_kIzone);
|
||||
// m_angleAdjusterPIDController.setFF(m_angleAdjusterGains.m_kF);
|
||||
// m_angleAdjusterPIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN / 5, m_angleAdjusterGains.m_kPeakOutput / 5);
|
||||
|
||||
// m_angleAdjusterPIDController.setReference(targetAngle, ControlType.kPosition);
|
||||
// }
|
||||
|
||||
/**
|
||||
* Runs The Hood
|
||||
* @param input The Speed Times 0.6
|
||||
/**
|
||||
* Set status of hood motor soft limits.
|
||||
* @param set Boolean to set soft limits to.
|
||||
*/
|
||||
public void runHood(double input) {
|
||||
input *= .6;
|
||||
m_angleAdjustMotor.set(input);
|
||||
public void setHoodSoftLimits(boolean set) {
|
||||
m_angleAdjusterMotor.enableSoftLimit(SoftLimitDirection.kForward, set);
|
||||
m_angleAdjusterMotor.enableSoftLimit(SoftLimitDirection.kReverse, set);
|
||||
}
|
||||
|
||||
public void runAngleAdjustPID(double targetAngle)
|
||||
{
|
||||
//Set PID Coefficients
|
||||
m_angleAdjusterPIDController.setP(m_angleAdjusterGains.kP);
|
||||
m_angleAdjusterPIDController.setI(m_angleAdjusterGains.kI);
|
||||
m_angleAdjusterPIDController.setD(m_angleAdjusterGains.kD);
|
||||
m_angleAdjusterPIDController.setIZone(m_angleAdjusterGains.kIzone);
|
||||
m_angleAdjusterPIDController.setFF(m_angleAdjusterGains.kF);
|
||||
m_angleAdjusterPIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN, m_angleAdjusterGains.kPeakOutput);
|
||||
|
||||
m_angleAdjusterPIDController.setReference(targetAngle, ControlType.kPosition);
|
||||
}
|
||||
|
||||
|
||||
public void runHood(double input) {
|
||||
m_angleAdjusterMotor.set(input);
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets The Encoder
|
||||
*/
|
||||
public void resetGyroAngleAdj(){
|
||||
m_angleEncoder.setPosition(0);
|
||||
}
|
||||
/**
|
||||
* Gets The Encoders Position
|
||||
* @return The Encoders Position
|
||||
*/
|
||||
public double getAnglePositionPID() {
|
||||
return m_angleEncoder.getPosition();
|
||||
|
||||
public double getAnglePosition(){
|
||||
return 0.0;//m_angleEncoder.getPosition();
|
||||
}
|
||||
|
||||
// public double getAnglePositionDegrees(){
|
||||
// return ((m_angleEncoder.getPosition() - ShooterConstants.HOOD_MOTOR_POS_AT_ZERO_ROT) * 360/ShooterConstants.HOOD_MOTOR_ROTS_PER_ROT) - 90;
|
||||
// }
|
||||
public double getAnglePositionDegrees(){
|
||||
return 0.0;//((m_angleEncoder.getPosition() - ShooterConstants.HOOD_MOTOR_POS_AT_ZERO_ROT) * 360/ShooterConstants.HOOD_MOTOR_ROTS_PER_ROT) - 90;
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user