diff --git a/src/main/java/frc/robot/subsystems/FeederSubsystem.java b/src/main/java/frc/robot/subsystems/FeederSubsystem.java index 71c14231..f44db26a 100644 --- a/src/main/java/frc/robot/subsystems/FeederSubsystem.java +++ b/src/main/java/frc/robot/subsystems/FeederSubsystem.java @@ -21,7 +21,7 @@ public class FeederSubsystem extends SubsystemBase{ public FeederSubsystem(){ //motors - feederMotor = new TalonFX(10); + feederMotor = new TalonFX(15); //sensors shooterSensor = new ColorSensorV3(I2C.Port.kMXP); diff --git a/src/main/java/frc/robot/subsystems/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/PivotSubsystem.java index 65f4ae4e..8bd245b4 100644 --- a/src/main/java/frc/robot/subsystems/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/PivotSubsystem.java @@ -15,7 +15,7 @@ public class PivotSubsystem extends SubsystemBase{ //final vars public final double PIVOT_SPEED = 0.1; final double GEARBOX_RATIO = 18.16; //ask cadders - public final int ERRORTOLERANCE = 10; //error tolerance for pid + public final int ERRORTOLERANCE = 5; //error tolerance for pid final int LIMIT_SWITCH_ID = 1; //placeholder //motors @@ -48,7 +48,7 @@ public class PivotSubsystem extends SubsystemBase{ public PivotSubsystem(boolean alliance){ //motors - pivotMotor = new CANSparkMax(10, MotorType.kBrushless); + pivotMotor = new CANSparkMax(12, MotorType.kBrushless); //devices rotationEncoder = pivotMotor.getEncoder(); diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 867562c7..ce1817a9 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -26,8 +26,8 @@ public class ShooterSubsystem extends SubsystemBase { public ShooterSubsystem(){ //motors - shooterMotor = new CANSparkMax(10, MotorType.kBrushless); - shooterMotorTwo = new CANSparkMax(10, MotorType.kBrushless); + shooterMotor = new CANSparkMax(13, MotorType.kBrushless); + shooterMotorTwo = new CANSparkMax(14, MotorType.kBrushless); //second motor shooter follows first shooterMotorTwo.follow(shooterMotor, true);