Skip to content

Commit 2d86cbe

Browse files
Changed TalonSRX to VictorSPX for Chimney and Intake.
1 parent a969116 commit 2d86cbe

File tree

2 files changed

+20
-11
lines changed

2 files changed

+20
-11
lines changed

src/main/java/org/mayheminc/robot2020/subsystems/Chimney.java

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -9,23 +9,30 @@
99

1010
import com.ctre.phoenix.motorcontrol.ControlMode;
1111
import com.ctre.phoenix.motorcontrol.NeutralMode;
12+
import com.ctre.phoenix.motorcontrol.can.VictorSPX;
1213

1314
import org.mayheminc.robot2020.Constants;
1415
import org.mayheminc.util.MayhemTalonSRX;
1516

17+
import edu.wpi.first.wpilibj.Victor;
1618
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1719
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1820

1921
public class Chimney extends SubsystemBase {
20-
private final MayhemTalonSRX chimneyTalon = new MayhemTalonSRX(Constants.Talon.MAGAZINE_CHIMNEY);
22+
private final VictorSPX chimneyTalon = new VictorSPX(Constants.Talon.MAGAZINE_CHIMNEY);
2123

2224
/**
2325
* Creates a new Chimney.
2426
*/
2527
public Chimney() {
2628
chimneyTalon.setNeutralMode(NeutralMode.Coast);
27-
chimneyTalon.configNominalOutputVoltage(+0.0f, -0.0f);
28-
chimneyTalon.configPeakOutputVoltage(+12.0, -12.0);
29+
// chimneyTalon.configNominalOutputVoltage(+0.0f, -0.0f);
30+
// chimneyTalon.configPeakOutputVoltage(+12.0, -12.0);
31+
chimneyTalon.configNominalOutputForward(+0.0f);
32+
chimneyTalon.configNominalOutputReverse(0.0);
33+
chimneyTalon.configPeakOutputForward(+12.0);
34+
chimneyTalon.configPeakOutputReverse(-12.0);
35+
2936
chimneyTalon.setInverted(true);
3037
}
3138

@@ -37,8 +44,8 @@ public void periodic() {
3744
}
3845

3946
void updateSmartDashboard() {
40-
SmartDashboard.putNumber("Chimney Speed", chimneyTalon.getSpeed());
41-
SmartDashboard.putNumber("Chimney Current", chimneyTalon.getStatorCurrent());
47+
SmartDashboard.putNumber("Chimney Speed", chimneyTalon.getMotorOutputPercent());
48+
// SmartDashboard.putNumber("Chimney Current", chimneyTalon.getStatorCurrent());
4249
}
4350

4451
void monitorTurntableMovement() {

src/main/java/org/mayheminc/robot2020/subsystems/Intake.java

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -11,18 +11,20 @@
1111
import com.ctre.phoenix.motorcontrol.DemandType;
1212
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
1313
import com.ctre.phoenix.motorcontrol.NeutralMode;
14+
import com.ctre.phoenix.motorcontrol.can.VictorSPX;
1415

1516
import org.mayheminc.robot2020.Constants;
1617
import org.mayheminc.util.MayhemTalonSRX;
1718
import org.mayheminc.util.PidTunerObject;
1819

20+
import edu.wpi.first.wpilibj.Victor;
1921
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2022
import edu.wpi.first.wpilibj2.command.SubsystemBase;
2123

2224
public class Intake extends SubsystemBase implements PidTunerObject {
2325

2426
private final int PIVOT_CLOSE_ENOUGH = 50;
25-
private final MayhemTalonSRX rollerTalon = new MayhemTalonSRX(Constants.Talon.INTAKE_ROLLERS);
27+
private final VictorSPX rollerTalon = new VictorSPX(Constants.Talon.INTAKE_ROLLERS);
2628
private final MayhemTalonSRX pivotTalon = new MayhemTalonSRX(Constants.Talon.INTAKE_PIVOT);
2729
private final int PIVOT_ZERO_POSITION = 900;
2830
public final double PIVOT_UP = 900.0;
@@ -44,8 +46,10 @@ enum PivotMode {
4446
*/
4547
public Intake() {
4648
rollerTalon.setNeutralMode(NeutralMode.Coast);
47-
rollerTalon.configNominalOutputVoltage(+0.0f, -0.0f);
48-
rollerTalon.configPeakOutputVoltage(+12.0, -12.0);
49+
rollerTalon.configNominalOutputForward(+0.0f);
50+
rollerTalon.configNominalOutputReverse(0.0);
51+
rollerTalon.configPeakOutputForward(+12.0);
52+
rollerTalon.configPeakOutputReverse(-12.0);
4953

5054
configPivotMotor(pivotTalon);
5155
}
@@ -93,12 +97,10 @@ public void zero() {
9397
*/
9498
public void setRollers(double power) {
9599
rollerTalon.set(ControlMode.PercentOutput, power);
96-
97100
}
98101

99102
public void setPivot(Double b) {
100103
m_targetPosition = b;
101-
// pivotTalon.set(ControlMode.Position, b);
102104

103105
mode = PivotMode.PID_MODE;
104106
isMoving = true;
@@ -159,7 +161,7 @@ public void updateSmartDashBoard() {
159161

160162
SmartDashboard.putBoolean("Intake Is Moving", isMoving);
161163
SmartDashboard.putBoolean("Intake PID Mode", (mode == PivotMode.PID_MODE));
162-
SmartDashboard.putNumber("Intake Rollers", rollerTalon.getMotorOutputVoltage());
164+
SmartDashboard.putNumber("Intake Rollers", rollerTalon.getMotorOutputPercent());
163165
}
164166

165167
public void setPivotVBus(double VBus) {

0 commit comments

Comments
 (0)