Skip to content

Commit db44649

Browse files
committed
Updated drivetrain wheels (6 in -> 4) and and changed motors to falcon motors
1 parent 236cf2a commit db44649

2 files changed

Lines changed: 29 additions & 31 deletions

File tree

src/main/java/frc/robot/constants/Constants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ public final class Constants {
8888
public static int SHOOTER_MAX_RPM = 6000;
8989
public static double SHOOTER_DEFAULT_RPM = 1250;
9090

91-
public static int WHEEL_DIAMETER = 6; //in inches
91+
public static int WHEEL_DIAMETER = 4; //in inches
9292
public static double WHEEL_DIAMETER_METERS = 0.1524;
9393

9494
public static double WHEEL_CIRCUMFERENCE_METERS = WHEEL_DIAMETER_METERS * Math.PI;

src/main/java/frc/robot/subsystems/RamseteDriveSubsystem.java

Lines changed: 28 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,7 @@
1313
import com.ctre.phoenix.motorcontrol.ControlMode;
1414
import com.ctre.phoenix.motorcontrol.DemandType;
1515
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
16-
import com.ctre.phoenix.motorcontrol.InvertType;
1716
import com.ctre.phoenix.motorcontrol.NeutralMode;
18-
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration;
19-
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
20-
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
2117
import com.kauailabs.navx.frc.AHRS;
2218

2319
import edu.wpi.first.networktables.EntryListenerFlags;
@@ -45,21 +41,24 @@
4541
import edu.wpi.first.wpiutil.math.MathUtil;
4642
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
4743
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
48-
44+
import com.ctre.phoenix.motorcontrol.TalonFXInvertType;
45+
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
4946
import frc.robot.constants.Constants;
5047
import frc.robot.constants.MotorConstants;
5148

49+
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration;
50+
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
5251
import frc.robot.util.Util;
5352

5453
public class RamseteDriveSubsystem extends SubsystemBase {
5554

56-
private final WPI_TalonSRX leftMaster = new WPI_TalonSRX(MotorConstants.kLeftMasterPort);
57-
private final WPI_VictorSPX leftFollower = new WPI_VictorSPX(MotorConstants.kLeftFollowerPort);
58-
private final WPI_VictorSPX leftFollower2 = new WPI_VictorSPX(MotorConstants.kLeftFollowerPort2);
55+
private final WPI_TalonFX leftMaster = new WPI_TalonFX(MotorConstants.kLeftMasterPort);
56+
private final WPI_TalonFX leftFollower = new WPI_TalonFX(MotorConstants.kLeftFollowerPort);
57+
5958

60-
private final WPI_TalonSRX rightMaster = new WPI_TalonSRX(MotorConstants.kRightMasterPort);
61-
private final WPI_VictorSPX rightFollower = new WPI_VictorSPX(MotorConstants.kRightFollowerPort);
62-
private final WPI_VictorSPX rightFollower2 = new WPI_VictorSPX(MotorConstants.kRightFollowerPort2);
59+
private final WPI_TalonFX rightMaster = new WPI_TalonFX(MotorConstants.kRightMasterPort);
60+
private final WPI_TalonFX rightFollower = new WPI_TalonFX(MotorConstants.kRightFollowerPort);
61+
6362

6463
private DifferentialDrive m_driveTrain;
6564

@@ -95,8 +94,14 @@ public RamseteDriveSubsystem() {
9594
resetEncoders();
9695
navX.zeroYaw();
9796

98-
TalonSRXConfiguration talonConfig = new TalonSRXConfiguration();
99-
talonConfig.primaryPID.selectedFeedbackSensor = FeedbackDevice.QuadEncoder;
97+
leftMaster.configFactoryDefault();
98+
rightMaster.configFactoryDefault();
99+
100+
101+
102+
103+
TalonFXConfiguration talonConfig = new TalonFXConfiguration();
104+
talonConfig.primaryPID.selectedFeedbackSensor = FeedbackDevice.IntegratedSensor;
100105
talonConfig.slot0.kP = Constants.kPDriveVel;
101106
talonConfig.slot0.kI = 0.0;
102107
talonConfig.slot0.kD = 0.0;
@@ -107,34 +112,31 @@ public RamseteDriveSubsystem() {
107112
leftMaster.configAllSettings(talonConfig);
108113
leftMaster.enableVoltageCompensation(true);
109114
leftFollower.configFactoryDefault();
110-
leftFollower2.configFactoryDefault();
115+
111116

112117
rightMaster.configAllSettings(talonConfig);
113118
rightMaster.enableVoltageCompensation(true);
114119
rightFollower.configFactoryDefault();
115-
rightFollower2.configFactoryDefault();
116-
120+
117121
enableEncoders();
118122

119123
setNeutralMode(NeutralMode.Brake);
120-
//uninvert right
121-
rightMaster.setSensorPhase(false);
122-
rightMaster.setInverted(false);
123-
rightFollower.setInverted(false);
124-
rightFollower2.setInverted(false);
125-
126-
leftMaster.setSensorPhase(true);
124+
125+
//Falcons don't need to set sensor phase
126+
//rightMaster.setSensorPhase(false);
127+
//rightMaster.setInverted(false);
128+
//rightFollower.setInverted(false);
129+
// leftMaster.setSensorPhase(true);
130+
131+
//uninvert right
127132
leftMaster.setInverted(false);
128133
leftFollower.setInverted(false);
129-
leftFollower2.setInverted(false);
130134

131135
rightMaster.overrideLimitSwitchesEnable(false);
132136
leftMaster.overrideLimitSwitchesEnable(false);
133137

134138
leftFollower.follow(leftMaster);
135-
leftFollower2.follow(leftMaster);
136139
rightFollower.follow(rightMaster);
137-
rightFollower2.follow(rightMaster);
138140

139141
//inversion etc has to happen BEFORE this statement!
140142
m_driveTrain = new DifferentialDrive(leftMaster, rightMaster);
@@ -265,12 +267,10 @@ public void tankDriveVelocity(double leftVelocity, double rightVelocity) {
265267
public void tankDriveVolts(double leftVolts, double rightVolts) {
266268
this.leftMaster.setVoltage(leftVolts);
267269
this.leftFollower.setVoltage(leftVolts);
268-
this.leftFollower2.setVoltage(leftVolts);
269270

270271
//if you're raw setting volts, you need to flip the right side.
271272
this.rightMaster.setVoltage(-rightVolts);
272273
this.rightFollower.setVoltage(-rightVolts);
273-
this.rightFollower2.setVoltage(-rightVolts);
274274
}
275275

276276

@@ -320,8 +320,6 @@ public void setNeutralMode(final NeutralMode neutralMode) {
320320
rightMaster.setNeutralMode(neutralMode);
321321
leftFollower.setNeutralMode(neutralMode);
322322
rightFollower.setNeutralMode(neutralMode);
323-
leftFollower2.setNeutralMode(neutralMode);
324-
rightFollower2.setNeutralMode(neutralMode);
325323
}
326324

327325
public void stop() {

0 commit comments

Comments
 (0)