mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 00:38:05 -06:00
commented out bunch of stuff in order to make turret work
This commit is contained in:
@@ -21,13 +21,13 @@ import frc4388.utility.Gains;
|
||||
public class Hood extends SubsystemBase {
|
||||
public BoomBoom m_shooterSubsystem;
|
||||
|
||||
public CANSparkMax m_angleAdjusterMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
|
||||
// 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 = m_angleAdjusterMotor.getEncoder();
|
||||
// public RelativeEncoder m_angleEncoder = m_angleAdjusterMotor.getEncoder();
|
||||
|
||||
public SparkMaxPIDController m_angleAdjusterPIDController = m_angleAdjusterMotor.getPIDController();
|
||||
// public SparkMaxPIDController m_angleAdjusterPIDController = m_angleAdjusterMotor.getPIDController();
|
||||
|
||||
|
||||
//public boolean m_isHoodReady = false;
|
||||
@@ -37,12 +37,12 @@ public double m_fireAngle;
|
||||
|
||||
/** Creates a new Hood. */
|
||||
public Hood() {
|
||||
m_angleAdjusterMotor.setIdleMode(IdleMode.kBrake);
|
||||
// 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_hoodUpLimitSwitch = m_angleAdjusterMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
// m_hoodDownLimitSwitch = m_angleAdjusterMotor.getReverseLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
|
||||
// m_hoodUpLimitSwitch.enableLimitSwitch(true);
|
||||
// m_hoodDownLimitSwitch.enableLimitSwitch(true);
|
||||
}
|
||||
|
||||
|
||||
@@ -53,30 +53,30 @@ public double m_fireAngle;
|
||||
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, m_angleAdjusterGains.m_kPeakOutput);
|
||||
// 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, m_angleAdjusterGains.m_kPeakOutput);
|
||||
|
||||
m_angleAdjusterPIDController.setReference(targetAngle, ControlType.kPosition);
|
||||
// m_angleAdjusterPIDController.setReference(targetAngle, ControlType.kPosition);
|
||||
}
|
||||
|
||||
|
||||
public void runHood(double input) {
|
||||
m_angleAdjusterMotor.set(input);
|
||||
// m_angleAdjusterMotor.set(input);
|
||||
}
|
||||
|
||||
public void resetGyroAngleAdj(){
|
||||
m_angleEncoder.setPosition(0);
|
||||
// m_angleEncoder.setPosition(0);
|
||||
}
|
||||
|
||||
public double getAnglePosition(){
|
||||
return m_angleEncoder.getPosition();
|
||||
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;
|
||||
return 0.0;//((m_angleEncoder.getPosition() - ShooterConstants.HOOD_MOTOR_POS_AT_ZERO_ROT) * 360/ShooterConstants.HOOD_MOTOR_ROTS_PER_ROT) - 90;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -28,7 +28,7 @@ public class Turret extends SubsystemBase {
|
||||
public BoomBoom m_boomBoomSubsystem;
|
||||
public SwerveDrive m_sDriveSubsystem;
|
||||
|
||||
public CANSparkMax m_boomBoomRotateMotor = new CANSparkMax(ShooterConstants.SHOOTER_ROTATE_ID, MotorType.kBrushless);
|
||||
public CANSparkMax m_boomBoomRotateMotor;// = new CANSparkMax(ShooterConstants.SHOOTER_ROTATE_ID, MotorType.kBrushless);
|
||||
public static Gains m_shooterTGains = ShooterConstants.SHOOTER_TURRET_GAINS;
|
||||
SparkMaxLimitSwitch m_boomBoomRightLimit, m_boomBoomLeftLimit;
|
||||
public Gyro m_turretGyro;
|
||||
@@ -37,14 +37,16 @@ public class Turret extends SubsystemBase {
|
||||
|
||||
public boolean m_isAimReady = false;
|
||||
|
||||
SparkMaxPIDController m_boomBoomRotatePIDController = m_boomBoomRotateMotor.getPIDController();
|
||||
public RelativeEncoder m_boomBoomRotateEncoder = m_boomBoomRotateMotor.getEncoder();
|
||||
SparkMaxPIDController m_boomBoomRotatePIDController;// = m_boomBoomRotateMotor.getPIDController();
|
||||
public RelativeEncoder m_boomBoomRotateEncoder;// = m_boomBoomRotateMotor.getEncoder();
|
||||
|
||||
|
||||
//Variables
|
||||
public Turret() {
|
||||
|
||||
|
||||
m_boomBoomRotateMotor = new CANSparkMax(30, MotorType.kBrushless);
|
||||
m_boomBoomRotatePIDController = m_boomBoomRotateMotor.getPIDController();
|
||||
m_boomBoomRotateEncoder = m_boomBoomRotateMotor.getEncoder();
|
||||
m_boomBoomRotateMotor.setIdleMode(IdleMode.kBrake);
|
||||
|
||||
m_turretGyro = getGyroInterface();
|
||||
|
||||
Reference in New Issue
Block a user