4141
4242public class IntakeShooter extends SubsystemBase {
4343 private final CANSparkMax intakeMotor = MotorControllerFactory .createSparkMax (INTAKE_PORT , MotorConfig .NEO_550 );
44- private final CANSparkMax outakeMotor = MotorControllerFactory .createSparkMax (10 , MotorConfig .NEO_550 );
45- // private final CANSparkFlex outakeMotorVortex = new CANSparkFlex(10,MotorType.kBrushless);
46- private final RelativeEncoder outakeEncoder = outakeMotor .getEncoder ();
44+ // private final CANSparkMax outakeMotor = MotorControllerFactory.createSparkMax(10, MotorConfig.NEO_550);
45+ private final CANSparkFlex outakeMotorVortex = new CANSparkFlex (10 ,MotorType .kBrushless );
46+ private final RelativeEncoder outakeEncoder = outakeMotorVortex .getEncoder ();
4747 private final RelativeEncoder intakeEncoder = intakeMotor .getEncoder ();
48- private final SparkPIDController pidControllerOutake = outakeMotor .getPIDController ();
48+ private final SparkPIDController pidControllerOutake = outakeMotorVortex .getPIDController ();
4949 private final SparkPIDController pidControllerIntake = intakeMotor .getPIDController ();
5050 private Timer timer = new Timer ();
5151 private int count = 0 ;
@@ -63,7 +63,7 @@ public class IntakeShooter extends SubsystemBase {
6363 public IntakeShooter () {
6464 //Figure out which ones to set inverted
6565 intakeMotor .setInverted (INTAKE_MOTOR_INVERSION );
66- outakeMotor .setInverted (OUTAKE_MOTOR_INVERSION );
66+ outakeMotorVortex .setInverted (OUTAKE_MOTOR_INVERSION );
6767 pidControllerOutake .setP (kP [OUTTAKE ]);
6868 pidControllerOutake .setI (kI [OUTTAKE ]);
6969 pidControllerOutake .setD (kD [OUTTAKE ]);
@@ -74,6 +74,7 @@ public IntakeShooter() {
7474 intakeEncoder .setAverageDepth (4 );
7575 intakeEncoder .setMeasurementPeriod (8 );
7676 SmartDashboard .putNumber ("intake volts" , 0 );
77+ SmartDashboard .putNumber ("Vortex volts" , 0 );
7778 // setMaxOutakeOverload(1);
7879
7980 }
@@ -90,7 +91,7 @@ private double getGamePieceDistanceIntake() {
9091 return Units .metersToInches (intakeDistanceSensor .getRange ()/1000 ) - DS_DEPTH_INCHES ;
9192 }
9293 public void motorSetOutake (int speed ) {
93- outakeMotor .set (speed );
94+ outakeMotorVortex .set (speed );
9495 }
9596 private double getGamePieceDistanceOutake () {
9697 return Units .metersToInches (OutakeDistanceSensor .getRange ()/1000 ) - DS_DEPTH_INCHES ;
@@ -133,11 +134,12 @@ public boolean outakeDetectsNote() {
133134
134135 @ Override
135136 public void periodic () {
136- outakeMotor .set (SmartDashboard .getNumber ("intake volts" , 0 ));
137- SmartDashboard .putNumber ("outtake vel" , outakeMotor .getEncoder ().getVelocity ());
137+ //outakeMotor.set(SmartDashboard.getNumber("intake volts", 0));
138+ SmartDashboard .putNumber ("outtake vel" , outakeMotorVortex .getEncoder ().getVelocity ());
139+
138140 //count++;
139- // double volts = SmartDashboard.getNumber("Vortex volts", 0);
140- // outakeMotorVortex.set(volts);
141+ double volts = SmartDashboard .getNumber ("Vortex volts" , 0 );
142+ // outakeMotorVortex.set(volts);
141143
142144 //setMaxOutake();
143145
@@ -154,16 +156,16 @@ public void setMaxIntake(int direction) {
154156
155157 }
156158 public void setMaxOutakeOverload (int direction ) {
157- outakeMotor .setSmartCurrentLimit (40 );
159+ // outakeMotor.setSmartCurrentLimit(40);
158160 //outakeMotor.setSmartCurrentLimit(1*direction);
159161 }
160162 public void setMaxOutake () {
161- outakeMotor .set (1 );
163+ outakeMotorVortex .set (1 );
162164 }
163165
164166 public void resetCurrentLimit () {
165167 intakeMotor .setSmartCurrentLimit (MotorConfig .NEO_550 .currentLimitAmps );
166- outakeMotor .setSmartCurrentLimit (MotorConfig .NEO .currentLimitAmps );
168+ // outakeMotorVortex .setSmartCurrentLimit(MotorConfig.NEO.currentLimitAmps);
167169 //intakeMotor.setSmartCurrentLimit(MotorConfig.NEO_550.currentLimitAmps);
168170 }
169171
@@ -184,7 +186,8 @@ public void stopOutake() {
184186 }
185187
186188 public void stopIntake () {
187- outakeMotor .set (0 );
189+ intakeMotor .set (0 );
190+ outakeMotorVortex .set (0 );
188191 }
189192 public double getIntakeRPM () {
190193 return intakeEncoder .getVelocity ();
0 commit comments