5
5
6
6
import com .ctre .phoenix .motorcontrol .*;
7
7
import com .ctre .phoenix .motorcontrol .ControlMode ;
8
+ import com .ctre .phoenix .motorcontrol .can .VictorSPX ;
8
9
9
10
import edu .wpi .first .wpilibj .Timer ;
10
11
import edu .wpi .first .wpilibj .smartdashboard .SmartDashboard ;
@@ -20,7 +21,7 @@ public class Shooter extends SubsystemBase implements PidTunerObject {
20
21
private final MayhemTalonSRX shooterWheelRight = new MayhemTalonSRX (Constants .Talon .SHOOTER_WHEEL_RIGHT );
21
22
private final MayhemTalonSRX turretTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_TURRET );
22
23
private final MayhemTalonSRX hoodTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_HOOD );
23
- private final MayhemTalonSRX feederTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_FEEDER );
24
+ private final VictorSPX feederTalon = new VictorSPX (Constants .Talon .SHOOTER_FEEDER );
24
25
25
26
// private final double MAX_SPEED_RPM = 5760.0;
26
27
private final double TALON_TICKS_PER_REV = 2048.0 ;
@@ -66,10 +67,13 @@ public void init() {
66
67
}
67
68
68
69
private void configureFeederTalon () {
69
- feederTalon .changeControlMode (ControlMode .PercentOutput );
70
+ // feederTalon.changeControlMode(ControlMode.PercentOutput);
70
71
feederTalon .setNeutralMode (NeutralMode .Brake );
71
- feederTalon .configNominalOutputVoltage (+0.0f , -0.0f );
72
- feederTalon .configPeakOutputVoltage (+6.0 , -6.0 );
72
+
73
+ feederTalon .configNominalOutputForward (+0.0f );
74
+ feederTalon .configNominalOutputReverse (0.0 );
75
+ feederTalon .configPeakOutputForward (+6.0 );
76
+ feederTalon .configPeakOutputReverse (-6.0 );
73
77
}
74
78
75
79
private void configureHoodTalon () {
@@ -198,7 +202,7 @@ private void UpdateDashboard() {
198
202
SmartDashboard .putNumber ("Shooter turret velocity" , turretTalon .getSelectedSensorVelocity (0 ));
199
203
200
204
SmartDashboard .putNumber ("Shooter hood pos" , hoodTalon .getPosition ());
201
- SmartDashboard .putNumber ("Shooter feeder speed" , feederTalon .getPosition ());
205
+ SmartDashboard .putNumber ("Shooter feeder speed" , feederTalon .getMotorOutputVoltage ());
202
206
203
207
// SmartDashboard.putNumber("Shooter Debug", debugShooter++);
204
208
}
0 commit comments