Skip to content

Commit 9e8a4d2

Browse files
committed
Clean up (see description)
- Organized the Constants.java and added some a reference table b/c why not - Commented out a lot of commands in RobotContainer.java; test subsystems one at one time initially - Added Constant.CANid references in some of the subsystems
1 parent c4be711 commit 9e8a4d2

File tree

7 files changed

+86
-49
lines changed

7 files changed

+86
-49
lines changed

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

Lines changed: 56 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
// Open Source Software; you can modify and/or share it under the terms of
33
// the WPILib BSD license file in the root directory of this project.
44

5+
6+
57
package frc.robot;
68

79
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
@@ -17,18 +19,20 @@
1719
*
1820
* <p>
1921
* It is advised to statically import this class (or one of its inner classes)
20-
* wherever the
21-
* constants are needed, to reduce verbosity.
22+
* wherever the constants are needed, to reduce verbosity.
2223
*/
2324
public final class Constants {
2425

25-
public int noteDistanceCheck = 100;
26+
/*Real world unit of millimeters
27+
* When less than this, the note status is considered "loaded"
28+
*/
29+
public static int NOTE_DISTANCE_CHECK = 100;
2630

2731
public static class OperatorConstants {
28-
public static final int K_DRIVER_CONTROLLER_PORT = 0;
29-
public static final int K_OPERATOR_CONTROLLER_PORT = 1;
32+
public static final int K_DRIVER_CONTROLLER_PORT = 0; // Driver Controller
33+
public static final int K_OPERATOR_CONTROLLER_PORT = 1; // Operator or Secondary Controller
3034

31-
public static final int DEFAULT_ARM_INCREMENT_VALUE = 20;
35+
public static final int DEFAULT_ARM_INCREMENT_VALUE = 20; // ?
3236

3337
}
3438

@@ -42,6 +46,7 @@ public static class SystemConstants {
4246
// For every 488 rotations of our driver motor, the arm makes 1 revolution.
4347
public static final double NET_ARM_RATIO = 458;
4448

49+
// Is this standard or added by us?
4550
public static class PID {
4651
public static final double DRIVE_P = 0.3f;
4752
public static final double DRIVE_I = 0;
@@ -63,16 +68,51 @@ public static class PID {
6368
}
6469

6570
public static class CANIDs {
66-
// ! DO NOT use CAN IDs 1-9; they are reserved for the modules and Pigeon
67-
68-
public static final int INTAKE_CAN = 10;
69-
public static final int INDEX_CAN = 11;
70-
71-
public static final int NOTE_SENSOR_ID = 12; // Time of Flight sensor for the note
72-
71+
72+
/* Hypothetical ID Table */
73+
74+
/* CAN IDs
75+
| Object | ID |
76+
|------------ |-----|
77+
| Drive FL | 01 |
78+
| Steer FL | 02 |
79+
| Drive FR | 03 |
80+
| Steer FR | 04 |
81+
| Drive RL | 05 |
82+
| Steer RL | 06 |
83+
| Drive RR | 07 |
84+
| Steer RR | 08 |
85+
| CANCoder FL | 09 |
86+
| CANCoder FR | 10 |
87+
| CANCoder RL | 11 |
88+
| CANCoder RR | 12 |
89+
| -Hard pass- | 13 |
90+
| Pidgeon | 14 |
91+
| Candle | 15 |
92+
93+
// Season Specific
94+
| Intake | 20 |
95+
| Index | 21 |
96+
| Arm | 22 |
97+
| Launcher LT | 23 |
98+
| Launcher RT | 24 |
99+
| Winch | 25 |
100+
| ToF Note | 42 |
101+
| Bass Guitar | |
102+
103+
*/
104+
105+
public static final int CANDLE_ID = 15; // Mini LED and LED strip controller
106+
public static final int INTAKE_ID = 20;
107+
public static final int INDEX_ID = 21;
108+
public static final int ARM_ID = 22;
109+
public static final int RIGHT_FLYWHEEL_ID = 23; // Right, when looking from back?
110+
public static final int LEFT_FLYWHEEL_ID = 24; //
111+
public static final int WINCH_ID = 25;
112+
public static final int NOTE_SENSOR_ID = 42; // Time of Flight sensor for the note
113+
114+
115+
// Extra CAN IDs
73116
public static final int BASS_GUITAR = 13;
74-
75-
public static final int RIGHT_FLYWHEEL_CAN = 15;
76-
public static final int LEFT_FLYWHEEL_CAN = 16;
77117
}
78118
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@
2626
import edu.wpi.first.networktables.GenericEntry;
2727
import edu.wpi.first.wpilibj2.command.Command;
2828
import edu.wpi.first.wpilibj2.command.InstantCommand;
29-
import edu.wpi.first.wpilibj2.command.RunCommand;
3029
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
3130
import frc.robot.generated.TunerConstants;
3231

@@ -86,8 +85,8 @@ public RobotContainer() {
8685

8786
Shuffleboard.getTab("Autos").add("Auton", autoChooser);
8887

89-
shooterMotorMain = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_CAN);
90-
shooterMotorSub = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_CAN);
88+
shooterMotorMain = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_ID);
89+
shooterMotorSub = new TalonFX(Constants.CANIDs.LEFT_FLYWHEEL_ID);
9190

9291
// #region some configs
9392

@@ -96,8 +95,8 @@ public RobotContainer() {
9695
shooterMotorMain.setNeutralMode(NeutralModeValue.Coast);
9796
shooterMotorMain.setNeutralMode(NeutralModeValue.Coast);
9897

99-
shooterMotorSub = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_CAN);
100-
shooterMotorMain = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_CAN);
98+
shooterMotorSub = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_ID);
99+
shooterMotorMain = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_ID);
101100
// #endregion
102101

103102
launcher = new LauncherSubsystem(shooterMotorMain, shooterMotorSub);
@@ -134,9 +133,9 @@ public RobotContainer() {
134133
// tl;dr: Trigger class for simple booleans
135134
private void configureBindings() {
136135

137-
m_driverController.a().whileTrue(drivetrain.applyRequest(() -> brake));
138-
m_driverController.b().whileTrue(drivetrain.applyRequest(() -> point
139-
.withModuleDirection(new Rotation2d(-m_driverController.getLeftY(), -m_driverController.getLeftX()))));
136+
// m_driverController.a().whileTrue(drivetrain.applyRequest(() -> brake));
137+
// m_driverController.b().whileTrue(drivetrain.applyRequest(() -> point
138+
// .withModuleDirection(new Rotation2d(-m_driverController.getLeftY(), -m_driverController.getLeftX()))));
140139

141140
// reset the field-centric heading on back press
142141
// Instant command because it doesn't set a requirment. In short, creating a
@@ -146,15 +145,18 @@ private void configureBindings() {
146145
// m_operatorController.back().onTrue(new InstantCommand(() ->
147146
// drivetrain.getPigeon2().setYaw(0)));
148147
// -------------------//-------------------//-------------------//-------------------//-------------------//-------------------
149-
m_operatorController.povUp().onTrue(winch.run(() -> winch.Drive(() -> 1)));
150-
m_operatorController.povDown().onTrue(winch.run(() -> winch.Drive(() -> -1)));
148+
// m_operatorController.povUp().onTrue(winch.run(() -> winch.Drive(() -> 1)));
149+
// m_operatorController.povDown().onTrue(winch.run(() -> winch.Drive(() -> -1)));
150+
151+
/* This ride is closed and undergoing maintence
151152
m_operatorController.y()
152153
.onTrue(
153154
arm.run(() -> arm.IncrementNativeUnits(incrementDistanceEntry.getInteger(DEFAULT_ARM_INCREMENT_VALUE))));
154155
m_operatorController.a()
155156
.onTrue(
156157
arm.run(() -> arm.IncrementNativeUnits(incrementDistanceEntry.getInteger(-DEFAULT_ARM_INCREMENT_VALUE))));
157158
159+
*/ // End of comment for incremental arm
158160
}
159161

160162
public void DebugMethodSingle() {

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

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,23 +1,14 @@
11
package frc.robot.subsystems;
22

3-
import java.io.NotActiveException;
43
import java.util.function.DoubleSupplier;
54

6-
import com.ctre.phoenix.motorcontrol.ControlMode;
7-
import com.ctre.phoenix6.configs.CustomParamsConfigs;
8-
import com.ctre.phoenix6.configs.HardwareLimitSwitchConfigs;
95
import com.ctre.phoenix6.configs.TalonFXConfiguration;
106
import com.ctre.phoenix6.controls.NeutralOut;
117
import com.ctre.phoenix6.controls.PositionDutyCycle;
12-
import com.ctre.phoenix6.controls.StaticBrake;
138
import com.ctre.phoenix6.controls.VelocityDutyCycle;
149
import com.ctre.phoenix6.hardware.TalonFX;
1510
import com.ctre.phoenix6.signals.NeutralModeValue;
16-
import com.fasterxml.jackson.databind.ser.std.NumberSerializers.DoubleSerializer;
17-
import com.playingwithfusion.CANVenom.BrakeCoastMode;
1811

19-
import edu.wpi.first.wpilibj.DigitalInput;
20-
import edu.wpi.first.wpilibj.DutyCycle;
2112
import edu.wpi.first.wpilibj2.command.SubsystemBase;
2213
import frc.robot.Constants;
2314

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

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,12 @@ public class IntakeSubsystem extends SubsystemBase {
2222

2323
public IntakeSubsystem() {
2424

25-
motor = new TalonFX(0);
25+
motor = new TalonFX(Constants.CANIDs.INTAKE_ID);
2626
dutyCycle = new DutyCycleOut(0);
2727
motor.setControl(dutyCycle);
2828

29-
notey.noteDistanceCheck = 3;
29+
int noteDistanceCheck = Constants.NOTE_DISTANCE_CHECK;
30+
3031
notey = new NoteSensorSubsystem();
3132
// Every 20ms it updates ()
3233

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

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
package frc.robot.subsystems;
22

3-
import java.util.function.DoubleSupplier;
4-
53
import com.ctre.phoenix6.controls.DutyCycleOut;
64
import com.ctre.phoenix6.hardware.TalonFX;
75

@@ -19,14 +17,14 @@ public class LauncherSubsystem extends SubsystemBase {
1917
/** As opposed to double */
2018
private boolean singleMotor;
2119

22-
private TalonFX m_main;
23-
private TalonFX m_sub;
20+
private TalonFX m_main; // The main motor
21+
private TalonFX m_secondary; // The secondary motor
2422
/** The state percentage */
2523
private double percentage;
2624
/** The multiplier that converts from "primary speed" to "secondary speed" */
2725
private double ratio = 1;
2826
private DutyCycleOut mainDutyCycle;
29-
private DutyCycleOut subDutyCycle;
27+
private DutyCycleOut secondaryDutyCycle;
3028

3129
// #region Diagnostics
3230
GenericEntry isRunning;
@@ -38,14 +36,14 @@ public class LauncherSubsystem extends SubsystemBase {
3836
* Set configs before creating this class/subsystem.
3937
* {@link #SetStatePower} is used to set the main power.
4038
*/
41-
public LauncherSubsystem(TalonFX main, TalonFX sub) {
39+
public LauncherSubsystem(TalonFX main, TalonFX secondary) {
4240

4341
singleMotor = false;
4442
this.m_main = main;
45-
this.m_sub = sub;
43+
this.m_secondary = secondary;
4644
// default to off
4745
m_main.setControl(mainDutyCycle = new DutyCycleOut(0));
48-
m_sub.setControl(subDutyCycle = new DutyCycleOut(0));
46+
m_secondary.setControl(secondaryDutyCycle = new DutyCycleOut(0));
4947

5048
}
5149

@@ -74,8 +72,8 @@ private void SetMotorPowers(double arg) {
7472
m_main.setControl(mainDutyCycle);
7573

7674
if (!singleMotor) {
77-
subDutyCycle.Output = arg * ratio * invertMulti;
78-
m_sub.setControl(subDutyCycle);
75+
secondaryDutyCycle.Output = arg * ratio * invertMulti;
76+
m_secondary.setControl(secondaryDutyCycle);
7977
}
8078
;
8179

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ CANdle requires the Phoenix (v5) vendordep
2323

2424

2525
public class LedSubsystem extends SubsystemBase{
26-
private final CANdle m_candle = new CANdle(Constants.CANIDs.NOTE_SENSOR_ID, "rio");
26+
private final CANdle m_candle = new CANdle(Constants.CANIDs.CANDLE_ID, "rio");
2727

2828
/* Update once the LEDs are installed if using Animations */
2929
// private final int LedCount = 69;

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

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,12 @@
55
import edu.wpi.first.wpilibj2.command.SubsystemBase;
66

77
public class MagLimitSwitch extends SubsystemBase{
8-
private DigitalInput limitSwitch = new DigitalInput(1); // figure out what actual outlet called
8+
9+
/* This could (should?) be moved into ArmSubsystem.java once tested. No other subsystem would use this limit switch */
10+
/* REV Magnetic Limit Switch
11+
* To be used for the arm for triggering a reset to the arm encoder when its position is "home"
12+
*/
13+
private DigitalInput limitSwitch = new DigitalInput(1);
914

1015
public boolean getSwitchState() {
1116
return limitSwitch.get();

0 commit comments

Comments
 (0)