Skip to content

Commit 8c079f3

Browse files
changed some unit stuff and finished indexer
1 parent 223de97 commit 8c079f3

33 files changed

+532
-562
lines changed

src/main/java/frc/robot/BuildConstants.java

Lines changed: 7 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -3,25 +3,15 @@
33
/** Automatically generated file containing build version information. */
44
public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
6-
public static final String MAVEN_NAME = "AdvantageKit_TalonFXSwerveTemplate";
6+
public static final String MAVEN_NAME = "2025TemplateRobotCode";
77
public static final String VERSION = "unspecified";
8-
<<<<<<< Updated upstream
9-
public static final int GIT_REVISION = 14;
10-
public static final String GIT_SHA = "71903e992f09d70d8dc29903114fa0ed607e07e7";
11-
public static final String GIT_DATE = "2024-11-10 16:32:20 EST";
12-
public static final String GIT_BRANCH = "subsystems-import";
13-
public static final String BUILD_DATE = "2024-11-10 17:28:21 EST";
14-
public static final long BUILD_UNIX_TIME = 1731277701353L;
8+
public static final int GIT_REVISION = 25;
9+
public static final String GIT_SHA = "684dd24387e9b57a008d05ee3e8e3cca5aee1f77";
10+
public static final String GIT_DATE = "2024-12-07 10:27:36 EST";
11+
public static final String GIT_BRANCH = "AK-files";
12+
public static final String BUILD_DATE = "2024-12-07 12:21:42 EST";
13+
public static final long BUILD_UNIX_TIME = 1733592102547L;
1514
public static final int DIRTY = 1;
16-
=======
17-
public static final int GIT_REVISION = -1;
18-
public static final String GIT_SHA = "UNKNOWN";
19-
public static final String GIT_DATE = "UNKNOWN";
20-
public static final String GIT_BRANCH = "UNKNOWN";
21-
public static final String BUILD_DATE = "2024-12-06 16:30:32 EST";
22-
public static final long BUILD_UNIX_TIME = 1733520632774L;
23-
public static final int DIRTY = 129;
24-
>>>>>>> Stashed changes
2515

2616
private BuildConstants() {}
2717
}

src/main/java/frc/robot/Robot.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import edu.wpi.first.wpilibj.Threads;
1717
import edu.wpi.first.wpilibj2.command.Command;
1818
import edu.wpi.first.wpilibj2.command.CommandScheduler;
19+
import frc.robot.constants.SimConstants;
1920
import org.littletonrobotics.junction.LogFileUtil;
2021
import org.littletonrobotics.junction.LoggedRobot;
2122
import org.littletonrobotics.junction.Logger;
@@ -53,7 +54,7 @@ public Robot() {
5354
}
5455

5556
// Set up data receivers & replay source
56-
switch (Constants.currentMode) {
57+
switch (SimConstants.currentMode) {
5758
case REAL:
5859
// Running on a real robot, log to a USB stick ("/U/logs")
5960
Logger.addDataReceiver(new WPILOGWriter());

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

Lines changed: 17 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,8 @@
1616
import static frc.robot.constants.VisionConstants.camera0Name;
1717
import static frc.robot.constants.VisionConstants.camera1Name;
1818

19-
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
20-
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
21-
2219
import com.pathplanner.lib.auto.AutoBuilder;
2320
import com.pathplanner.lib.auto.NamedCommands;
24-
2521
import edu.wpi.first.math.geometry.Pose2d;
2622
import edu.wpi.first.math.geometry.Rotation2d;
2723
import edu.wpi.first.wpilibj.GenericHID;
@@ -31,7 +27,8 @@
3127
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
3228
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
3329
import frc.robot.commands.DriveCommands;
34-
import frc.robot.constants.PhysicalConstants;
30+
import frc.robot.constants.SimConstants;
31+
import frc.robot.constants.TunerConstants;
3532
import frc.robot.subsystems.drive.Drive;
3633
import frc.robot.subsystems.drive.GyroIO;
3734
import frc.robot.subsystems.drive.GyroIOPigeon2;
@@ -41,10 +38,11 @@
4138
import frc.robot.subsystems.flywheel.Flywheel;
4239
import frc.robot.subsystems.flywheel.FlywheelIO;
4340
import frc.robot.subsystems.flywheel.FlywheelIOSim;
44-
import frc.robot.subsystems.flywheel.FlywheelIOSparkMax;
41+
import frc.robot.subsystems.flywheel.FlywheelIOTalonFX;
4542
import frc.robot.subsystems.vision.Vision;
4643
import frc.robot.subsystems.vision.VisionIO;
4744
import frc.robot.subsystems.vision.VisionIOLimelight;
45+
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
4846

4947
/**
5048
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -63,23 +61,21 @@ public class RobotContainer {
6361

6462
// Dashboard inputs
6563
private final LoggedDashboardChooser<Command> autoChooser;
66-
private final LoggedDashboardNumber flywheelSpeedInput =
67-
new LoggedDashboardNumber("Flywheel Speed", 1500.0);
6864

6965
/** The container for the robot. Contains subsystems, OI devices, and commands. */
7066
public RobotContainer() {
71-
switch (PhysicalConstants.currentMode) {
67+
switch (SimConstants.currentMode) {
7268
case REAL:
7369
// Real robot, instantiate hardware IO implementations
7470
drive =
7571
new Drive(
76-
new GyroIOPigeon2(false),
77-
new ModuleIOTalonFX(0),
78-
new ModuleIOTalonFX(1),
79-
new ModuleIOTalonFX(2),
80-
new ModuleIOTalonFX(3));
72+
new GyroIOPigeon2(),
73+
new ModuleIOTalonFX(TunerConstants.FrontLeft),
74+
new ModuleIOTalonFX(TunerConstants.FrontRight),
75+
new ModuleIOTalonFX(TunerConstants.BackLeft),
76+
new ModuleIOTalonFX(TunerConstants.BackRight));
8177

82-
flywheel = new Flywheel(new FlywheelIOSparkMax());
78+
flywheel = new Flywheel(new FlywheelIOTalonFX());
8379
vision =
8480
new Vision(
8581
drive::addVisionMeasurement,
@@ -100,12 +96,12 @@ public RobotContainer() {
10096
drive =
10197
new Drive(
10298
new GyroIO() {},
103-
new ModuleIOSim(),
104-
new ModuleIOSim(),
105-
new ModuleIOSim(),
106-
new ModuleIOSim());
99+
new ModuleIOSim(TunerConstants.FrontLeft),
100+
new ModuleIOSim(TunerConstants.FrontRight),
101+
new ModuleIOSim(TunerConstants.BackLeft),
102+
new ModuleIOSim(TunerConstants.BackRight));
107103
vision = new Vision(drive::addVisionMeasurement, new VisionIO() {}, new VisionIO() {});
108-
104+
109105
flywheel = new Flywheel(new FlywheelIOSim());
110106

111107
break;
@@ -127,8 +123,7 @@ public RobotContainer() {
127123
// Set up auto routines
128124
NamedCommands.registerCommand(
129125
"Run Flywheel",
130-
Commands.startEnd(
131-
() -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel)
126+
Commands.startEnd(() -> flywheel.runVelocity(500), flywheel::stop, flywheel)
132127
.withTimeout(5.0));
133128
autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser());
134129

@@ -181,11 +176,6 @@ private void configureButtonBindings() {
181176
new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
182177
drive)
183178
.ignoringDisable(true));
184-
controller
185-
.a()
186-
.whileTrue(
187-
Commands.startEnd(
188-
() -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel));
189179
}
190180

191181
/**

src/main/java/frc/robot/Constants.java renamed to src/main/java/frc/robot/constants/SimConstants.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
1212
// GNU General Public License for more details.
1313

14-
package frc.robot;
14+
package frc.robot.constants;
1515

1616
import edu.wpi.first.wpilibj.RobotBase;
1717

@@ -20,7 +20,7 @@
2020
* on a roboRIO. Change the value of "simMode" to switch between "sim" (physics sim) and "replay"
2121
* (log replay from a file).
2222
*/
23-
public final class Constants {
23+
public final class SimConstants {
2424
public static final Mode simMode = Mode.SIM;
2525
public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode;
2626

src/main/java/frc/robot/constants/PhysicalConstants.java renamed to src/main/java/frc/robot/constants/SubsystemConstants.java

Lines changed: 4 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -11,34 +11,14 @@
1111
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
1212
// GNU General Public License for more details.
1313

14+
// does not include swerve constants
15+
1416
package frc.robot.constants;
1517

16-
import edu.wpi.first.math.util.Units;
18+
public final class SubsystemConstants {
1719

18-
public final class PhysicalConstants {
19-
public static final Mode currentMode = Mode.REAL;
20-
public static final boolean tuningMode = true;
2120
public static final String CANBUS = "CAN Bus 2";
22-
public static final double LOOP_PERIOD_SECS = 0.02;
23-
24-
public static final String LL_ALIGN = "limelight-align";
25-
public static final double INTAKE_LL_ANGLE = -20;
26-
public static final double INTAKE_LL_HEIGHT_METERS = 0.5;
27-
28-
public static class SwerveConstants {
29-
public static final double MAX_LINEAR_SPEED = 5.56;
30-
public static final double TRACK_WIDTH_X_METERS = Units.inchesToMeters(26.0);
31-
public static final double TRACK_WIDTH_Y_METERS = Units.inchesToMeters(26.0);
32-
public static final double DRIVE_BASE_RADIUS =
33-
Math.hypot(TRACK_WIDTH_X_METERS / 2.0, TRACK_WIDTH_Y_METERS / 2.0);
34-
public static final double MAX_ANGULAR_SPEED = 0.45 * MAX_LINEAR_SPEED / DRIVE_BASE_RADIUS;
35-
public static final double OPEN_LOOP_RAMP_SEC = 0.05;
36-
}
37-
38-
public static class ModuleConstants {
39-
public static final double DRIVE_GEAR_RATIO = 6.12;
40-
public static final double TURN_GEAR_RATIO = 150.0 / 7.0;
41-
}
21+
public static final double LOOP_PERIOD_SECONDS = 0.02;
4222

4323
public static class IntakeConstants {
4424
public static final int CURRENT_LIMIT = 40;
@@ -104,12 +84,4 @@ public static enum Mode {
10484
SIM,
10585
REPLAY
10686
}
107-
108-
public static Mode getMode() {
109-
return switch (currentMode) {
110-
case REAL -> Mode.REAL;
111-
case SIM -> Mode.SIM;
112-
case REPLAY -> Mode.REPLAY;
113-
};
114-
}
11587
}

src/main/java/frc/robot/subsystems/arms/Pivot.java

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,18 @@
44

55
package frc.robot.subsystems.arms;
66

7+
import static edu.wpi.first.units.Units.Degrees;
8+
import static edu.wpi.first.units.Units.DegreesPerSecond;
9+
import static edu.wpi.first.units.Units.Volts;
10+
711
import edu.wpi.first.math.MathUtil;
812
import edu.wpi.first.math.controller.ArmFeedforward;
913
import edu.wpi.first.math.trajectory.TrapezoidProfile;
14+
import edu.wpi.first.units.measure.Angle;
15+
import edu.wpi.first.units.measure.AngularVelocity;
1016
import edu.wpi.first.wpilibj2.command.SubsystemBase;
11-
import frc.robot.constants.PhysicalConstants;
12-
17+
import frc.robot.constants.SimConstants;
18+
import frc.robot.constants.SubsystemConstants;
1319
import org.littletonrobotics.junction.Logger;
1420

1521
public class Pivot extends SubsystemBase {
@@ -36,7 +42,7 @@ public class Pivot extends SubsystemBase {
3642
/** Creates a new Pivot. */
3743
public Pivot(PivotIO pivot) {
3844
this.pivot = pivot;
39-
switch (PhysicalConstants.getMode()) {
45+
switch (SimConstants.currentMode) {
4046
case REAL:
4147
kG = 0.29;
4248
kV = 1;
@@ -96,7 +102,11 @@ public void setPositionDegs(double positionDegs, double velocityDegsPerSec) {
96102
positionDegs = MathUtil.clamp(positionDegs, 33, 120);
97103
pivot.setPositionSetpointDegs(
98104
positionDegs,
99-
pivotFFModel.calculate(Math.toRadians(positionDegs), Math.toRadians(velocityDegsPerSec)));
105+
pivotFFModel
106+
.calculate(
107+
Angle.ofBaseUnits(positionDegs, Degrees),
108+
AngularVelocity.ofBaseUnits(velocityDegsPerSec, DegreesPerSecond))
109+
.in(Volts));
100110
}
101111

102112
public void pivotStop() {
@@ -118,7 +128,9 @@ public void periodic() {
118128

119129
pivotCurrentStateDegrees =
120130
pivotProfile.calculate(
121-
PhysicalConstants.LOOP_PERIOD_SECS, pivotCurrentStateDegrees, pivotGoalStateDegrees);
131+
SubsystemConstants.LOOP_PERIOD_SECONDS,
132+
pivotCurrentStateDegrees,
133+
pivotGoalStateDegrees);
122134

123135
setPositionDegs(pivotCurrentStateDegrees.position, pivotCurrentStateDegrees.velocity);
124136

src/main/java/frc/robot/subsystems/arms/PivotIOSim.java

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -7,17 +7,15 @@
77
import edu.wpi.first.math.MathUtil;
88
import edu.wpi.first.math.controller.PIDController;
99
import edu.wpi.first.math.system.plant.DCMotor;
10-
import edu.wpi.first.math.system.plant.LinearSystemId;
1110
import edu.wpi.first.math.util.Units;
1211
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
13-
import frc.robot.constants.physicalConstants;
12+
import frc.robot.constants.SubsystemConstants;
1413

1514
/** Add your docs here. */
1615
public class PivotIOSim implements PivotIO {
1716
// private final DCMotor pivotGearbox = DCMotor.getKrakenX60Foc(2);
18-
17+
1918
// public RobotContainer robotContainer = new RobotContainer();
20-
2119

2220
// SIM VARIABLES
2321
private int gearBoxMotorCount = 2;
@@ -73,7 +71,7 @@ public void updateInputs(PivotIOInputs inputs) {
7371
inputs.velocityDegsPerSec = Math.toDegrees(velocityRadsPerSec);
7472
inputs.currentAmps = currentAmps;
7573

76-
sim.update(physicalConstants.LOOP_PERIOD_SECS);
74+
sim.update(SubsystemConstants.LOOP_PERIOD_SECONDS);
7775
}
7876

7977
@Override

0 commit comments

Comments
 (0)