Skip to content

Commit cd9d9aa

Browse files
Changes from Saturday, 22 Feb at Mayhem and at field: (1) Added second shooter wheel Falcon. (2) Switched PID Tuner back to shooter. (3) Code changes for removal of climber ratchet. (It works!)
1 parent ff47b3d commit cd9d9aa

File tree

5 files changed

+80
-55
lines changed

5 files changed

+80
-55
lines changed

src/main/java/org/mayheminc/robot2020/Constants.java

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,13 @@
2020
public final class Constants {
2121

2222
public final class Talon {
23-
public static final int DRIVE_RIGHT_A = 3; // high current
24-
public static final int DRIVE_RIGHT_B = 4; // high current
2523
public static final int DRIVE_LEFT_A = 1; // high current
2624
public static final int DRIVE_LEFT_B = 2; // high current
25+
public static final int DRIVE_RIGHT_A = 3; // high current
26+
public static final int DRIVE_RIGHT_B = 4; // high current
2727

28-
public static final int SHOOTER_WHEEL = 5; // high current
28+
public static final int SHOOTER_WHEEL_LEFT = 5; // high current
29+
public static final int SHOOTER_WHEEL_RIGHT = 17; // high current
2930
public static final int SHOOTER_FEEDER = 6;
3031
public static final int SHOOTER_TURRET = 7;
3132
public static final int SHOOTER_HOOD = 8;
@@ -41,7 +42,7 @@ public final class Talon {
4142
public static final int CLIMBER_WALKER_LEFT = 15;
4243
public static final int CLIMBER_WALKER_RIGHT = 16;
4344

44-
public static final int CONTROL_PANEL_ROLLER = 17; // WON"T FIT!!!
45+
public static final int CONTROL_PANEL_ROLLER = 18; // WON"T FIT!!!
4546
}
4647

4748
public final class Solenoid {

src/main/java/org/mayheminc/robot2020/RobotContainer.java

Lines changed: 3 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ public RobotContainer() {
6262
pidtuner = new PidTuner(RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_SIX,
6363
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_SEVEN,
6464
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_ELEVEN,
65-
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_TEN, intake);
65+
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_TEN, shooter);
6666

6767
cameraLights.set(true);
6868
}
@@ -166,16 +166,12 @@ private void configureDriverPadButtons() {
166166
// Debug shooter pid velocity
167167
DRIVER_PAD.DRIVER_PAD_BLUE_BUTTON.whenPressed(new ShooterAdjustWheel(100.0));
168168
DRIVER_PAD.DRIVER_PAD_GREEN_BUTTON.whenPressed(new ShooterAdjustWheel(-100.0));
169-
DRIVER_PAD.DRIVER_PAD_RED_BUTTON.whenPressed(new ShooterSetWheel(0.0));
169+
DRIVER_PAD.DRIVER_PAD_RED_BUTTON.whenPressed(new ShooterSetWheelVBus(0.0));
170170
DRIVER_PAD.DRIVER_PAD_YELLOW_BUTTON.whenPressed(new ShooterSetWheel(3000));
171171
// TODO: above hard-coded constant (3000) should be a named constant from Shooter.java
172172

173173
DRIVER_PAD.DRIVER_PAD_LEFT_UPPER_TRIGGER_BUTTON.whileHeld(new ShooterSetFeeder(1.0));
174174

175-
// debug climber pistons
176-
// DRIVER_PAD.DRIVER_PAD_D_PAD_UP.whenPressed(new ClimberSetPistons(true));
177-
// DRIVER_PAD.DRIVER_PAD_D_PAD_UP.whenPressed(new ClimberSetPistons(false));
178-
179175
}
180176

181177
private void configureOperatorStickButtons() {
@@ -206,8 +202,7 @@ private void configureOperatorPadButtons() {
206202
OPERATOR_PAD.OPERATOR_PAD_D_PAD_UP.whileHeld(new ShooterSetHoodVBus(+1.0));
207203
OPERATOR_PAD.OPERATOR_PAD_D_PAD_DOWN.whileHeld(new ShooterSetHoodVBus(-1.0));
208204

209-
// OPERATOR_PAD.OPERATOR_PAD_RIGHT_Y_AXIS_UP.whileHeld(new
210-
// ClimberSetWinchesPower(0.7));
205+
OPERATOR_PAD.OPERATOR_PAD_RIGHT_Y_AXIS_UP.whileHeld(new ClimberSetWinchesPower(0.7));
211206
OPERATOR_PAD.OPERATOR_PAD_RIGHT_Y_AXIS_DOWN.whileHeld(new ClimberSetWinchesPower(-0.7));
212207

213208
// OPERATOR_PAD.OPERATOR_PAD_LEFT_Y_AXIS_UP.whenPressed(new

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

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@
2020
public class Climber extends SubsystemBase {
2121
private final MayhemTalonSRX winchLeft = new MayhemTalonSRX(Constants.Talon.CLIMBER_WINCH_LEFT);
2222
private final MayhemTalonSRX winchRight = new MayhemTalonSRX(Constants.Talon.CLIMBER_WINCH_RIGHT);
23-
private final MayhemTalonSRX walkerLeft = new MayhemTalonSRX(Constants.Talon.CLIMBER_WALKER_LEFT);
24-
private final MayhemTalonSRX walkerRight = new MayhemTalonSRX(Constants.Talon.CLIMBER_WALKER_RIGHT);
23+
// private final MayhemTalonSRX walkerLeft = new MayhemTalonSRX(Constants.Talon.CLIMBER_WALKER_LEFT);
24+
// private final MayhemTalonSRX walkerRight = new MayhemTalonSRX(Constants.Talon.CLIMBER_WALKER_RIGHT);
2525

2626
private final Solenoid pistons = new Solenoid(Constants.Solenoid.CLIMBER_PISTONS);
2727

@@ -37,13 +37,13 @@ public Climber() {
3737
winchRight.configNominalOutputVoltage(+0.0f, -0.0f);
3838
winchRight.configPeakOutputVoltage(+12.0, -12.0);
3939

40-
walkerRight.setNeutralMode(NeutralMode.Brake);
41-
walkerRight.configNominalOutputVoltage(+0.0f, -0.0f);
42-
walkerRight.configPeakOutputVoltage(+12.0, -12.0);
40+
// walkerRight.setNeutralMode(NeutralMode.Brake);
41+
// walkerRight.configNominalOutputVoltage(+0.0f, -0.0f);
42+
// walkerRight.configPeakOutputVoltage(+12.0, -12.0);
4343

44-
walkerLeft.setNeutralMode(NeutralMode.Brake);
45-
walkerLeft.configNominalOutputVoltage(+0.0f, -0.0f);
46-
walkerLeft.configPeakOutputVoltage(+12.0, -12.0);
44+
// walkerLeft.setNeutralMode(NeutralMode.Brake);
45+
// walkerLeft.configNominalOutputVoltage(+0.0f, -0.0f);
46+
// walkerLeft.configPeakOutputVoltage(+12.0, -12.0);
4747

4848
}
4949

@@ -70,13 +70,13 @@ public void setWinchRightSpeed(double power) {
7070
winchRight.set(ControlMode.PercentOutput, power);
7171
}
7272

73-
public void setWalkerLeftSpeed(double power) {
74-
walkerLeft.set(ControlMode.Velocity, power);
75-
}
73+
// public void setWalkerLeftSpeed(double power) {
74+
// walkerLeft.set(ControlMode.Velocity, power);
75+
// }
7676

77-
public void setWalkerRightSpeed(double power) {
78-
walkerRight.set(ControlMode.Velocity, power);
79-
}
77+
// public void setWalkerRightSpeed(double power) {
78+
// walkerRight.set(ControlMode.Velocity, power);
79+
// }
8080

8181
public void setPistons(boolean b) {
8282
pistons.set(b);

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

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ public class Drive extends SubsystemBase {
2727
public static final boolean COAST_MODE = false;
2828

2929
// PID loop variables
30+
// TODO: Suppress 'deprecated' warnings from the compiler
3031
private PIDController m_HeadingPid;
3132
private PIDHeadingError m_HeadingError;
3233
private PIDHeadingCorrection m_HeadingCorrection;

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

Lines changed: 57 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,8 @@
1616
import org.mayheminc.util.PidTunerObject;
1717

1818
public class Shooter extends SubsystemBase implements PidTunerObject {
19-
private final MayhemTalonSRX shooterWheelTalon = new MayhemTalonSRX(Constants.Talon.SHOOTER_WHEEL);
19+
private final MayhemTalonSRX shooterWheelLeft = new MayhemTalonSRX(Constants.Talon.SHOOTER_WHEEL_LEFT);
20+
private final MayhemTalonSRX shooterWheelRight = new MayhemTalonSRX(Constants.Talon.SHOOTER_WHEEL_RIGHT);
2021
private final MayhemTalonSRX turretTalon = new MayhemTalonSRX(Constants.Talon.SHOOTER_TURRET);
2122
private final MayhemTalonSRX hoodTalon = new MayhemTalonSRX(Constants.Talon.SHOOTER_HOOD);
2223
private final MayhemTalonSRX feederTalon = new MayhemTalonSRX(Constants.Talon.SHOOTER_FEEDER);
@@ -47,20 +48,24 @@ public class Shooter extends SubsystemBase implements PidTunerObject {
4748
* Creates a new Shooter.
4849
*/
4950
public Shooter() {
51+
configureWheelFalcons();
5052
configureTurretTalon();
51-
configureWheelTalon();
5253
configureHoodTalon();
5354
configureFeederTalon();
5455

55-
shooterWheelTalon.config_kP(0, 3.0, 0);
56-
shooterWheelTalon.config_kI(0, 0.0, 0);
57-
shooterWheelTalon.config_kD(0, 0.0, 0);
58-
shooterWheelTalon.config_kF(0, 0.048); // 1023.0 / convertRpmToTicksPer100ms(5760), 0);
56+
shooterWheelLeft.config_kP(0, 3.0, 0);
57+
shooterWheelLeft.config_kI(0, 0.0, 0);
58+
shooterWheelLeft.config_kD(0, 0.0, 0);
59+
shooterWheelLeft.config_kF(0, 0.046); // 1023.0 / convertRpmToTicksPer100ms(5760), 0);
60+
61+
// set right Falcon to follow the left Falcon
62+
shooterWheelRight.changeControlMode(ControlMode.Follower);
63+
shooterWheelRight.set(shooterWheelLeft.getDeviceID());
5964
}
6065

6166
public void init() {
67+
configureWheelFalcons();
6268
configureTurretTalon();
63-
configureWheelTalon();
6469
configureHoodTalon();
6570
configureFeederTalon();
6671

@@ -120,11 +125,20 @@ void configureTurretTalon() {
120125
this.setTurretVBus(0.0);
121126
}
122127

123-
private void configureWheelTalon() {
124-
shooterWheelTalon.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
125-
shooterWheelTalon.setNeutralMode(NeutralMode.Coast);
126-
shooterWheelTalon.configNominalOutputVoltage(+0.0f, -0.0f);
127-
shooterWheelTalon.configPeakOutputVoltage(+12.0, 0.0);
128+
private void configureWheelFalcons() {
129+
shooterWheelLeft.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
130+
shooterWheelLeft.setNeutralMode(NeutralMode.Coast);
131+
shooterWheelLeft.configNominalOutputVoltage(+0.0f, -0.0f);
132+
shooterWheelLeft.configPeakOutputVoltage(+12.0, 0.0);
133+
shooterWheelLeft.setInverted(false);
134+
shooterWheelLeft.setSensorPhase(false);
135+
136+
shooterWheelRight.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
137+
shooterWheelRight.setNeutralMode(NeutralMode.Coast);
138+
shooterWheelRight.configNominalOutputVoltage(+0.0f, -0.0f);
139+
shooterWheelRight.configPeakOutputVoltage(+12.0, 0.0);
140+
shooterWheelRight.setInverted(true);
141+
shooterWheelRight.setSensorPhase(true);
128142
}
129143

130144
@Override
@@ -150,15 +164,29 @@ public double getAzimuthForCapturedImage() {
150164
}
151165

152166
private void UpdateDashboard() {
153-
SmartDashboard.putNumber("Shooter Wheel pos", shooterWheelTalon.getSelectedSensorPosition(0));
154-
SmartDashboard.putNumber("Shooter Wheel speed", shooterWheelTalon.getSelectedSensorVelocity(0));
167+
SmartDashboard.putNumber("Shooter Wheel pos", shooterWheelLeft.getSelectedSensorPosition(0));
168+
SmartDashboard.putNumber("Shooter Wheel speed", shooterWheelLeft.getSelectedSensorVelocity(0));
155169
SmartDashboard.putNumber("Shooter Wheel RPM",
156-
convertTicksPer100msToRPM(shooterWheelTalon.getSelectedSensorVelocity(0)));
170+
convertTicksPer100msToRPM(shooterWheelLeft.getSelectedSensorVelocity(0)));
157171

158172
SmartDashboard.putNumber("Shooter Wheel target RPM", m_targetSpeedRPM);
159173
SmartDashboard.putNumber("Shooter Wheel Error",
160-
m_targetSpeedRPM - convertTicksPer100msToRPM(shooterWheelTalon.getSelectedSensorVelocity(0)));
161-
SmartDashboard.putNumber("Shooter Wheel Voltage", shooterWheelTalon.getMotorOutputVoltage());
174+
m_targetSpeedRPM - convertTicksPer100msToRPM(shooterWheelLeft.getSelectedSensorVelocity(0)));
175+
SmartDashboard.putNumber("Shooter Wheel Voltage", shooterWheelLeft.getMotorOutputVoltage());
176+
SmartDashboard.putNumber("Shooter Wheel Bus Voltage", shooterWheelLeft.getBusVoltage());
177+
SmartDashboard.putNumber("Shooter Wheel Current", shooterWheelLeft.getSupplyCurrent());
178+
179+
SmartDashboard.putNumber("Shooter Wheel R-pos", shooterWheelRight.getSelectedSensorPosition(0));
180+
SmartDashboard.putNumber("Shooter Wheel R-speed", shooterWheelRight.getSelectedSensorVelocity(0));
181+
SmartDashboard.putNumber("Shooter Wheel R-RPM",
182+
convertTicksPer100msToRPM(shooterWheelRight.getSelectedSensorVelocity(0)));
183+
184+
SmartDashboard.putNumber("Shooter Wheel R-target RPM", m_targetSpeedRPM);
185+
SmartDashboard.putNumber("Shooter Wheel R-Error",
186+
m_targetSpeedRPM - convertTicksPer100msToRPM(shooterWheelRight.getSelectedSensorVelocity(0)));
187+
SmartDashboard.putNumber("Shooter Wheel R-Voltage", shooterWheelRight.getMotorOutputVoltage());
188+
SmartDashboard.putNumber("Shooter Wheel R-Bus Voltage", shooterWheelRight.getBusVoltage());
189+
SmartDashboard.putNumber("Shooter Wheel R-Current", shooterWheelRight.getSupplyCurrent());
162190

163191
SmartDashboard.putNumber("Shooter turret pos", turretTalon.getPosition());
164192
SmartDashboard.putNumber("Shooter turret vbus", turretTalon.getMotorOutputVoltage());
@@ -235,67 +263,67 @@ public void setFeederSpeed(double pos) {
235263
public void setShooterWheelSpeed(double rpm) {
236264
double ticks = convertRpmToTicksPer100ms(rpm);
237265
m_targetSpeedRPM = rpm;
238-
shooterWheelTalon.set(ControlMode.Velocity, ticks);
266+
shooterWheelLeft.set(ControlMode.Velocity, ticks);
239267
}
240268

241269
public void setShooterWheelSpeedVBus(double pos) {
242-
shooterWheelTalon.set(ControlMode.PercentOutput, pos);
270+
shooterWheelLeft.set(ControlMode.PercentOutput, pos);
243271
}
244272

245273
public double getShooterWheelSpeed() {
246-
return convertTicksPer100msToRPM(shooterWheelTalon.getSelectedSensorVelocity(0));
274+
return convertTicksPer100msToRPM(shooterWheelLeft.getSelectedSensorVelocity(0));
247275
}
248276

249277
public double getShooterWheelTargetSpeed() {
250278
return m_targetSpeedRPM;
251279
}
252280

253281
public double getShooterWheelSpeedVBus() {
254-
return shooterWheelTalon.getMotorOutputVoltage();
282+
return shooterWheelLeft.getMotorOutputVoltage();
255283
}
256284

257285
////////////////////////////////////////////////////
258286
// PidTunerObject
259287
@Override
260288
public double getP() {
261-
return turretTalon.getP();
289+
return shooterWheelLeft.getP();
262290
}
263291

264292
@Override
265293
public double getI() {
266-
return turretTalon.getI();
294+
return shooterWheelLeft.getI();
267295
}
268296

269297
@Override
270298
public double getD() {
271-
return turretTalon.getD();
299+
return shooterWheelLeft.getD();
272300
}
273301

274302
@Override
275303
public double getF() {
276-
return turretTalon.getF();
304+
return shooterWheelLeft.getF();
277305

278306
}
279307

280308
@Override
281309
public void setP(double d) {
282-
turretTalon.config_kP(0, d, 0);
310+
shooterWheelLeft.config_kP(0, d, 0);
283311
}
284312

285313
@Override
286314
public void setI(double d) {
287-
turretTalon.config_kI(0, d, 0);
315+
shooterWheelLeft.config_kI(0, d, 0);
288316
}
289317

290318
@Override
291319
public void setD(double d) {
292-
turretTalon.config_kD(0, d, 0);
320+
shooterWheelLeft.config_kD(0, d, 0);
293321

294322
}
295323

296324
@Override
297325
public void setF(double d) {
298-
turretTalon.config_kF(0, d, 0);
326+
shooterWheelLeft.config_kF(0, d, 0);
299327
}
300328

301329
}

0 commit comments

Comments
 (0)