diff --git a/.github/scripts/visualizeStates.py b/.github/scripts/visualizeStates.py new file mode 100644 index 0000000..281ea9d --- /dev/null +++ b/.github/scripts/visualizeStates.py @@ -0,0 +1,184 @@ +import sys +import re +from pathlib import Path +from graphviz import Digraph + +# ---------- Parsing ManagerStates ---------- +def get_manager_states(manager_states_path): + text = Path(manager_states_path).read_text(encoding="utf8") + + pattern = re.compile( + r""" + (\w+)\s* + \(\s* + "(.*?)"\s*,\s* + ([^,]+)\s*,\s* + ([^,]+)\s*,\s* + ([^,]+)\s*,\s* + ([^)]+) + \) + """, + re.VERBOSE | re.DOTALL, + ) + + states = {} + + for m in pattern.finditer(text): + name = m.group(1) + + def clean(x: str) -> str: + x = x.strip() + x = re.sub(r".*?\.", "", x) + x = re.sub(r"\(.*\)", "", x) + return x + + states[name] = { + "Intake": clean(m.group(3)), + "Hopper": clean(m.group(4)), + "Shooter": clean(m.group(5)), + "Climber": clean(m.group(6)), + "connectionsTo": [], + } + + return states + +# ---------- Parsing Triggers ---------- +def get_triggers(manager_path): + file = Path(manager_path).read_text(encoding="utf8") + return re.findall(r"addTrigger\([\s\S]*?\);", file) + +def parse_triggers(triggers): + parsed = [] + + for t in triggers: + m = re.search( + r""" + addTrigger\( + \s*(?:\w+\.)?(\w+)\s*, # from + \s*(?:\w+\.)?(\w+)\s*, # to + \s*(.*?) # condition (FULL) + \)\s*; + """, + t, + re.VERBOSE | re.DOTALL, + ) + if not m: + continue + + condition = m.group(3).strip() + + # Remove lambda wrapper + condition = re.sub(r"^\(\)\s*->\s*", "", condition) + + # Remove controller prefixes + condition = re.sub(r"(?:DRIVER|OPERATOR)_CONTROLLER::get", "", condition) + condition = re.sub(r".*?::", "", condition) + + parsed.append({ + "from": m.group(1), + "to": m.group(2), + "condition": condition, + }) + + return parsed + +def attach_triggers(state_map, triggers): + for t in triggers: + if t["from"] in state_map: + state_map[t["from"]]["connectionsTo"].append(t) + +# ---------- Graphviz helpers ---------- +def node_id(name: str) -> str: + return re.sub(r"\W+", "_", name) + +EDGE_COLORS = [ + "#f6e05e", "#68d391", "#63b3ed", "#fc8181", + "#90cdf4", "#faf089", "#fbb6ce", "#9f7aea" +] + +# ---------- Visualization ---------- +def generate_graph(state_map): + dot = Digraph("StateMachine", format="png", engine="dot") + + dot.attr( + rankdir="TB", + bgcolor="#1e1e2f", + fontname="Helvetica", + nodesep="0.6", + ranksep="0.9", + ) + + dot.attr( + "node", + shape="box", + style="rounded,filled", + fillcolor="#2d2d3c", + color="#68d391", + fontcolor="white", + fontname="Helvetica-Bold", + fontsize="11", + penwidth="1.4", + ) + + dot.attr( + "edge", + fontname="Helvetica", + fontsize="9", + arrowsize="0.8", + ) + + # Nodes + for state, info in state_map.items(): + lines = [ + f"{state}", + "────────────", + f"Intake → {info['Intake']}", + f"Hopper → {info['Hopper']}", + f"Shooter → {info['Shooter']}", + f"Climber → {info['Climber']}", + ] + label = "\n".join(lines) + + if state == "IDLE": + dot.node( + node_id(state), + label=label, + fillcolor="#3e2c1c", + color="#f6ad55", + penwidth="2.5", + ) + else: + dot.node(node_id(state), label=label) + + # Edges + color_index = 0 + for state, info in state_map.items(): + if not info["connectionsTo"]: + continue + + color = EDGE_COLORS[color_index % len(EDGE_COLORS)] + color_index += 1 + + for c in info["connectionsTo"]: + dot.edge( + node_id(state), + node_id(c["to"]), + label=c["condition"], + color=color, + fontcolor=color, + penwidth="1.8", + ) + + dot.render("state_machine", cleanup=True) + print("Rendered state_machine.png") + +# ---------- Main ---------- +def main(managerStatesPath, managerPath): + state_map = get_manager_states(managerStatesPath) + triggers = parse_triggers(get_triggers(managerPath)) + attach_triggers(state_map, triggers) + generate_graph(state_map) + print("Success!") + +if __name__ == "__main__": + main(sys.argv[1], sys.argv[2]) diff --git a/.github/workflows/visualizeStates.yml b/.github/workflows/visualizeStates.yml new file mode 100644 index 0000000..6e3d5e8 --- /dev/null +++ b/.github/workflows/visualizeStates.yml @@ -0,0 +1,61 @@ +name: Visualize States + +on: + pull_request: + types: + - reopened + - opened + - synchronize + +jobs: + generate-graph: + runs-on: ubuntu-latest + steps: + - name: Checkout repo + uses: actions/checkout@v3 + + - name: Install system dependencies + run: | + sudo apt-get update + sudo apt-get install -y graphviz + + - name: Set up Python + uses: actions/setup-python@v4 + with: + python-version: '3.x' + + - name: Install dependencies + run: | + pip install graphviz + + - name: Run graph generation + id: run-script + run: | + python3 .github/scripts/visualizeStates.py ./src/main/java/frc/robot/Subsystems/Manager/ManagerStates.java ./src/main/java/frc/robot/Subsystems/Manager/Manager.java + echo "exit_code=$?" >> $GITHUB_OUTPUT + continue-on-error: true + + - name: Upload graph as artifact + uses: actions/upload-artifact@v4 + with: + name: state-machine-graph + path: state_machine.png + + - name: Comment on PR + uses: actions/github-script@v6 + with: + script: | + const prNumber = context.payload.pull_request.number; + const exitCode = Number(process.env.EXIT_CODE); + const commentBody = exitCode === 0 + ? "✅ State machine graph generated and uploaded." + : "⚠️ Something went wrong while generating the state machine graph."; + + github.rest.issues.createComment({ + issue_number: prNumber, + owner: context.repo.owner, + repo: context.repo.repo, + body: commentBody + }) + env: + EXIT_CODE: ${{ steps.run-script.outputs.exit_code }} \ No newline at end of file diff --git a/Other/AscopeFiles/PutAscopeModelsAndConfigHere.txt b/Other/AscopeFiles/PutAscopeModelsAndConfigHere.txt new file mode 100644 index 0000000..15ebd22 --- /dev/null +++ b/Other/AscopeFiles/PutAscopeModelsAndConfigHere.txt @@ -0,0 +1 @@ +hmm \ No newline at end of file diff --git a/Other/Dashboards/PutDriverDashBoardHere.txt b/Other/Dashboards/PutDriverDashBoardHere.txt new file mode 100644 index 0000000..3824fbb --- /dev/null +++ b/Other/Dashboards/PutDriverDashBoardHere.txt @@ -0,0 +1 @@ +hmmmmmm \ No newline at end of file diff --git a/Other/Sim/GoatedSimConfig.json b/Other/Sim/GoatedSimConfig.json new file mode 100644 index 0000000..5deaf70 --- /dev/null +++ b/Other/Sim/GoatedSimConfig.json @@ -0,0 +1,143 @@ +{ + "Docking": { + "Data": [ + "DockNode ID=0x00000002 Pos=-2,2 Size=1926,1098 Split=X", + "DockNode ID=0x00000001 Parent=0x00000002 SizeRef=1153,1095 Split=Y", + "DockNode ID=0x0000000F Parent=0x00000001 SizeRef=991,210 Split=X", + "DockNode ID=0x0000000D Parent=0x0000000F SizeRef=519,140 Split=X", + "DockNode ID=0x0000000B Parent=0x0000000D SizeRef=257,140 Selected=0x39AD1970", + "DockNode ID=0x0000000C Parent=0x0000000D SizeRef=280,140 Selected=0xD58031C5", + "DockNode ID=0x0000000E Parent=0x0000000F SizeRef=632,140 Selected=0x513EDE86", + "DockNode ID=0x00000010 Parent=0x00000001 SizeRef=991,883 Split=Y Selected=0xB5CBE9F0", + "DockNode ID=0x00000012 Parent=0x00000010 SizeRef=1153,233 Split=Y Selected=0xF9AD29AD", + "DockNode ID=0x00000014 Parent=0x00000012 SizeRef=1155,199 Selected=0x5446CBB7", + "DockNode ID=0x00000015 Parent=0x00000012 SizeRef=1155,240 Selected=0xF9AD29AD", + "DockNode ID=0x00000013 Parent=0x00000010 SizeRef=1153,650 Selected=0xB5CBE9F0", + "DockNode ID=0x00000011 Parent=0x00000002 SizeRef=767,1095 Split=Y", + "DockNode ID=0x00000007 Parent=0x00000011 SizeRef=313,611 Split=X Selected=0x3E3C37F1", + "DockNode ID=0x00000003 Parent=0x00000007 SizeRef=309,746 Selected=0x3E3C37F1", + "DockNode ID=0x00000004 Parent=0x00000007 SizeRef=458,746 Selected=0x2D9B9756", + "DockNode ID=0x00000008 Parent=0x00000011 SizeRef=313,287 Split=Y Selected=0x6AE6D891", + "DockNode ID=0x00000005 Parent=0x00000008 SizeRef=313,32 Split=X Selected=0x6AE6D891", + "DockNode ID=0x00000009 Parent=0x00000005 SizeRef=295,176 Selected=0x6AE6D891", + "DockNode ID=0x0000000A Parent=0x00000005 SizeRef=472,176 Selected=0xC8493FD8", + "DockNode ID=0x00000006 Parent=0x00000008 SizeRef=313,316 Selected=0x138219D4" + ] + }, + "MainWindow": { + "GLOBAL": { + "font": "Roboto Bold", + "fps": "120", + "height": "1051", + "maximized": "1", + "style": "3", + "userScale": "2", + "width": "1920", + "xpos": "0", + "ypos": "29" + } + }, + "Window": { + "###/AdvantageKit/RealOutputs/Alerts": { + "Collapsed": "0", + "Pos": "137,171", + "Size": "300,148" + }, + "###/FMSInfo": { + "Collapsed": "0", + "Pos": "60,60", + "Size": "168,206" + }, + "###/SmartDashboard/Auto Chooser": { + "Collapsed": "0", + "DockId": "0x0000000E,0", + "Pos": "521,20", + "Size": "633,211" + }, + "###/SmartDashboard/Field": { + "Collapsed": "0", + "DockId": "0x00000013,0", + "Pos": "-2,450", + "Size": "1155,650" + }, + "###/SmartDashboard/VisionSystemSim-Vision/Sim Field": { + "Collapsed": "0", + "DockId": "0x00000015,0", + "Pos": "-1,233", + "Size": "1155,441" + }, + "###/SmartDashboard/VisionSystemSim-main/Sim Field": { + "Collapsed": "0", + "DockId": "0x00000014,0", + "Pos": "-2,215", + "Size": "1155,233" + }, + "###FMS": { + "Collapsed": "0", + "DockId": "0x0000000A,0", + "Pos": "1452,750", + "Size": "472,32" + }, + "###Joysticks": { + "Collapsed": "0", + "DockId": "0x00000006,0", + "Pos": "1155,784", + "Size": "769,316" + }, + "###Keyboard 0 Settings": { + "Collapsed": "0", + "DockId": "0x00000003,0", + "Pos": "1156,20", + "Size": "309,746" + }, + "###NetworkTables": { + "Collapsed": "0", + "DockId": "0x00000004,0", + "Pos": "1155,2", + "Size": "769,746" + }, + "###NetworkTables Info": { + "Collapsed": "0", + "Pos": "939,136", + "Size": "681,492" + }, + "###Other Devices": { + "Collapsed": "0", + "Pos": "558,386", + "Size": "312,1173" + }, + "###Plot <0>": { + "Collapsed": "0", + "Pos": "65,61", + "Size": "700,400" + }, + "###PowerDistributions": { + "Collapsed": "0", + "Pos": "245,155", + "Size": "200,456" + }, + "###System Joysticks": { + "Collapsed": "0", + "DockId": "0x00000009,0", + "Pos": "1155,750", + "Size": "295,32" + }, + "###Timing": { + "Collapsed": "0", + "DockId": "0x0000000C,0", + "Pos": "552,2", + "Size": "601,211" + }, + "Debug##Default": { + "Collapsed": "0", + "Pos": "60,60", + "Size": "400,400" + }, + "Robot State": { + "Collapsed": "0", + "DockId": "0x0000000B,0", + "Pos": "-2,2", + "Size": "552,211" + } + } +} \ No newline at end of file diff --git a/simgui-ds.json b/simgui-ds.json new file mode 100644 index 0000000..8c3a26b --- /dev/null +++ b/simgui-ds.json @@ -0,0 +1,98 @@ +{ + "keyboardJoysticks": [ + { + "axisConfig": [ + { + "decKey": 65, + "incKey": 68 + }, + { + "decKey": 87, + "incKey": 83 + }, + { + "decKey": 69, + "decayRate": 0.0, + "incKey": 82, + "keyRate": 0.009999999776482582 + } + ], + "axisCount": 3, + "buttonCount": 4, + "buttonKeys": [ + 90, + 88, + 67, + 86 + ], + "povConfig": [ + { + "key0": 328, + "key135": 323, + "key180": 322, + "key225": 321, + "key270": 324, + "key315": 327, + "key45": 329, + "key90": 326 + } + ], + "povCount": 1 + }, + { + "axisConfig": [ + { + "decKey": 74, + "incKey": 76 + }, + { + "decKey": 73, + "incKey": 75 + } + ], + "axisCount": 2, + "buttonCount": 4, + "buttonKeys": [ + 77, + 44, + 46, + 47 + ], + "povCount": 0 + }, + { + "axisConfig": [ + { + "decKey": 263, + "incKey": 262 + }, + { + "decKey": 265, + "incKey": 264 + } + ], + "axisCount": 2, + "buttonCount": 6, + "buttonKeys": [ + 260, + 268, + 266, + 261, + 269, + 267 + ], + "povCount": 0 + }, + { + "axisCount": 0, + "buttonCount": 0, + "povCount": 0 + } + ], + "robotJoysticks": [ + { + "guid": "030000004c050000c405000000000000", + "useGamepad": true + } + ] +} diff --git a/src/main/java/frc/robot/GlobalConstants.java b/src/main/java/frc/robot/GlobalConstants.java index a180182..7ad7b98 100644 --- a/src/main/java/frc/robot/GlobalConstants.java +++ b/src/main/java/frc/robot/GlobalConstants.java @@ -4,16 +4,15 @@ import edu.wpi.first.units.measure.LinearAcceleration; import edu.wpi.first.units.measure.Mass; -import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.XboxController; -import edu.wpi.first.wpilibj.XboxController; -import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.Field2d; import java.util.ArrayList; import java.util.Arrays; public class GlobalConstants { + public static final int VOLTS = 12; + public static final LinearAcceleration GRAVITY = MetersPerSecondPerSecond.of(9.81); public static final double SIMULATION_PERIOD = 0.02; // TODO: This is wrong @@ -32,12 +31,23 @@ public enum RobotMode { public static class Controllers { public static final XboxController DRIVER_CONTROLLER = new XboxController(0); - public static final GenericHID OPERATOR_CONTROLLER = new GenericHID(1); + public static final XboxController OPERATOR_CONTROLLER = new XboxController(1); public static final XboxController TEST_CONTROLLER = new XboxController(4); // NOTE: Set to 0.1 on trash controllers - public static final double DEADBAND = 0.01; + public static final double DEADBAND = 0.15; public static final double TRIGGERS_REGISTER_POINT = 0.5; + + /** + * Apply the configured deadband to a controller axis value. + * Returns 0.0 when the absolute value is below DEADBAND, otherwise returns the original value. + * + * @param value axis value in range [-1, 1] + * @return value with deadband applied + */ + public static double applyDeadband(double value) { + return Math.abs(value) < DEADBAND ? 0.0 : value; + } } public static class FaultManagerConstants { @@ -45,6 +55,5 @@ public static class FaultManagerConstants { public static final ArrayList CANIVORE_DEVICE_ORDER = new ArrayList(Arrays.asList(39, 56, 6, 4, 58, 9, 5, 11, 12, 2, 59, 3, 8)); } - public static final double DEADBAND = 0.01; public static final double TRIGGERS_REGISTER_POINT = 0.5; } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index e01e05f..14b8b41 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -1,54 +1,88 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - package frc.robot; -import edu.wpi.first.wpilibj.TimedRobot; +import static frc.robot.Subsystems.Manager.ManagerStates.IDLE; -/** - * The methods in this class are called automatically corresponding to each mode, as described in - * the TimedRobot documentation. If you change the name of this class or the package after creating - * this project, you must also update the Main.java file in the project. - */ -public class Robot extends TimedRobot { +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.Subsystems.Drive.Drive; +import frc.robot.Subsystems.Manager.Manager; +import org.littletonrobotics.junction.LoggedRobot; +import org.littletonrobotics.junction.Logger; +import org.littletonrobotics.junction.networktables.NT4Publisher; +import org.littletonrobotics.junction.wpilog.WPILOGWriter; +import org.team7525.misc.CommandsUtil; +import org.team7525.misc.Tracer; - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - public Robot() {} +public class Robot extends LoggedRobot { - @Override - public void robotPeriodic() {} + private final Manager manager = Manager.getInstance(); + + public static boolean isRedAlliance = true; @Override - public void autonomousInit() {} + public void robotInit() { + switch (GlobalConstants.ROBOT_MODE) { + case REAL: + Logger.addDataReceiver(new NT4Publisher()); + Logger.addDataReceiver(new WPILOGWriter()); + break; + case SIM: + Logger.addDataReceiver(new NT4Publisher()); + break; + case TESTING: + Logger.addDataReceiver(new NT4Publisher()); + break; + } + + // Lots and lots of trolling + Logger.start(); + CommandsUtil.logCommands(); + DriverStation.silenceJoystickConnectionWarning(true); + CommandScheduler.getInstance().unregisterAllSubsystems(); + System.gc(); + Drive.getInstance().zeroGyro(); + } @Override - public void autonomousPeriodic() {} + public void robotPeriodic() { + Tracer.startTrace("RobotPeriodic"); + CommandScheduler.getInstance().run(); + Tracer.traceFunc("SubsystemManager", manager::periodic); + Tracer.endTrace(); + } @Override - public void teleopInit() {} + public void autonomousInit() {} @Override - public void teleopPeriodic() {} + public void autonomousPeriodic() {} @Override - public void disabledInit() {} + public void autonomousExit() { + CommandScheduler.getInstance().cancelAll(); + } @Override - public void disabledPeriodic() {} + public void teleopInit() { + manager.setState(IDLE); + } @Override - public void testInit() {} + public void teleopPeriodic() {} @Override - public void testPeriodic() {} + public void disabledInit() { + System.gc(); + } @Override - public void simulationInit() {} + public void disabledPeriodic() { + isRedAlliance = DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red; + } @Override - public void simulationPeriodic() {} + public void disabledExit() { + isRedAlliance = DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red; + } } diff --git a/src/main/java/frc/robot/Subsystems/Climber/ClimberConstants.java b/src/main/java/frc/robot/Subsystems/Climber/ClimberConstants.java index aec6244..4e77534 100644 --- a/src/main/java/frc/robot/Subsystems/Climber/ClimberConstants.java +++ b/src/main/java/frc/robot/Subsystems/Climber/ClimberConstants.java @@ -10,8 +10,8 @@ public class ClimberConstants { public static final String SUBSYSTEM_NAME = "Climber"; - public static final int LEFT_CLIMBER_MOTOR_ID = 20; - public static final int RIGHT_CLIMBER_MOTOR_ID = 21; + public static final int LEFT_CLIMBER_MOTOR_ID = 30; + public static final int RIGHT_CLIMBER_MOTOR_ID = 31; public static final Supplier CLIMB_PID = () -> switch (GlobalConstants.ROBOT_MODE) { case REAL -> new PIDController(1.0, 0.0, 0.0); diff --git a/src/main/java/frc/robot/Subsystems/Drive/Drive.java b/src/main/java/frc/robot/Subsystems/Drive/Drive.java index b6d188b..924e14f 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/Drive.java +++ b/src/main/java/frc/robot/Subsystems/Drive/Drive.java @@ -21,6 +21,8 @@ import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import frc.robot.GlobalConstants.RobotMode; +import frc.robot.Subsystems.Drive.DriveIO.DriveIOOutputs; import frc.robot.Subsystems.Drive.TunerConstants.TunerSwerveDrivetrain; import org.littletonrobotics.junction.Logger; import org.team7525.subsystem.Subsystem; @@ -30,17 +32,12 @@ public class Drive extends Subsystem { private static Drive instance; private DriveIO driveIO; - private DriveIOInputsAutoLogged inputs = new DriveIOInputsAutoLogged(); + private DriveIOOutputs inputs = new DriveIOOutputs(); private boolean robotMirrored = false; private Pose2d lastPose = new Pose2d(); private double lastTime = 0; private final Field2d field = new Field2d(); - /** - * Constructs a new Drive subsystem with the given DriveIO. - * - * @param driveIO The DriveIO object used for controlling the drive system. - */ private Drive() { super("Drive", DriveStates.FIELD_RELATIVE); this.driveIO = switch (ROBOT_MODE) { @@ -58,11 +55,6 @@ private Drive() { ); } - /** - * Returns the singleton instance of the Drive subsystem. - * - * @return The Drive Instance. - */ public static Drive getInstance() { if (instance == null) { instance = new Drive(); @@ -72,8 +64,15 @@ public static Drive getInstance() { @Override public void runState() { - driveIO.updateInputs(inputs); - Logger.processInputs("Drive", inputs); + driveIO.logOutputs(inputs); + Logger.recordOutput(SUBSYSTEM_NAME + "/Gyro Angle Deg", inputs.gyroAngleDeg); + Logger.recordOutput(SUBSYSTEM_NAME + "/Robot Angle Deg", inputs.robotAngleDeg); + Logger.recordOutput(SUBSYSTEM_NAME + "/Full Robot Rotation", inputs.fullRobotRotation); + Logger.recordOutput(SUBSYSTEM_NAME + "/Failed Data Acquisitions", inputs.failedDataAquisitions); + Logger.recordOutput(SUBSYSTEM_NAME + "/Timestamp", inputs.timestamp); + Logger.recordOutput(SUBSYSTEM_NAME + "/Chassis Speeds", inputs.speeds); + Logger.recordOutput(SUBSYSTEM_NAME + "/Set Points", inputs.setPoints); + Logger.recordOutput(SUBSYSTEM_NAME + "/Odometry Frequency", inputs.odometryFrequency); if (DriverStation.isDisabled()) robotMirrored = false; @@ -87,15 +86,15 @@ public void runState() { } logOutputs(driveIO.getDrive().getState()); + // Otherwise it will try to force wheels to stop in auto + //if (AutoAlign.getInstance().getState() == AutoAlignStates.OFF) { + getState().driveRobot(); + //} + field.setRobotPose(getPose()); SmartDashboard.putData("Field", field); } - /** - * Logs the outputs of the drive system. - * - * @param state The current state of the SwerveDrive. - */ public void logOutputs(SwerveDriveState state) { Logger.recordOutput(SUBSYSTEM_NAME + "/Robot Pose", state.Pose); Logger.recordOutput(SUBSYSTEM_NAME + "/Current Time", Utils.getSystemTimeSeconds()); @@ -113,35 +112,32 @@ public void logOutputs(SwerveDriveState state) { } public void driveFieldRelative(double xVelocity, double yVelocity, double angularVelocity) { - driveIO.setControl( - new SwerveRequest.FieldCentric() - .withDeadband(frc.robot.GlobalConstants.Controllers.DEADBAND) - .withVelocityX(xVelocity) - .withVelocityY(yVelocity) - .withRotationalRate(angularVelocity) - .withDriveRequestType(SwerveModule.DriveRequestType.Velocity) - .withSteerRequestType(SwerveModule.SteerRequestType.MotionMagicExpo) - .withRotationalDeadband(1) - ); + driveIO.setControl(new SwerveRequest.FieldCentric().withDeadband(DEADBAND).withVelocityX(xVelocity).withVelocityY(yVelocity).withRotationalRate(angularVelocity).withDriveRequestType(SwerveModule.DriveRequestType.Velocity).withSteerRequestType(SwerveModule.SteerRequestType.MotionMagicExpo)); } public void driveRobotRelative(double xVelocity, double yVelocity, double angularVelocity) { - driveIO.setControl( - new SwerveRequest.RobotCentric() - .withDeadband(frc.robot.GlobalConstants.Controllers.DEADBAND) - .withVelocityX(xVelocity) - .withVelocityY(yVelocity) - .withRotationalRate(angularVelocity) - .withDriveRequestType(SwerveModule.DriveRequestType.Velocity) - .withSteerRequestType(SwerveModule.SteerRequestType.MotionMagicExpo) - .withRotationalDeadband(1) - ); + driveIO.setControl(new SwerveRequest.RobotCentric().withDeadband(DEADBAND).withVelocityX(xVelocity).withVelocityY(yVelocity).withRotationalRate(angularVelocity).withDriveRequestType(SwerveModule.DriveRequestType.Velocity).withSteerRequestType(SwerveModule.SteerRequestType.MotionMagicExpo)); } public void zeroGyro() { driveIO.zeroGyro(); } + public boolean isAtAllianceShootingPosition() { + return true; + // var allianceOpt = DriverStation.getAlliance(); + // if (allianceOpt.isEmpty()) { + // // Alliance not yet known (e.g., early init). Treat as not at alliance shooting position. + // return false; + // } + // Alliance alliance = allianceOpt.get(); + // if (alliance == Alliance.Red) { + // return getPose().getTranslation().getX() > ALLIANCE_SHOOTING_POSITION_THRESHOLD_RED.in(Meters); + // } else { + // return getPose().getTranslation().getX() < -ALLIANCE_SHOOTING_POSITION_THRESHOLD_BLUE.in(Meters); + // } + } + // Util public Pose2d getPose() { return driveIO.getDrive().getState().Pose; diff --git a/src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java b/src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java index d01e9e2..ee33e4c 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java +++ b/src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java @@ -10,7 +10,6 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.LinearAcceleration; -import edu.wpi.first.units.measure.LinearVelocity; public class DriveConstants { @@ -19,10 +18,7 @@ public class DriveConstants { public static final Distance WHEEL_BASE = Meters.of(0.5); public static final double MIN_SCALE_FACTOR = 0.1; - //This changes how fast/how slow the angular velocity scales down as height increases - public static final double ANGULAR_VELOCITY_SCALE_FACTOR = 1.0; - // TODO: Change based on PP constants public static final LinearAcceleration MAX_LINEAR_ACCELERATION = MetersPerSecondPerSecond.of(11.7); public static final AngularVelocity ANGULAR_VELOCITY_LIMIT = AngularVelocity.ofBaseUnits(180, DegreesPerSecond); @@ -30,10 +26,6 @@ public class DriveConstants { public static final LinearAcceleration MAX_LINEAR_DECELERATION = MetersPerSecondPerSecond.of(11); public static final LinearAcceleration MAX_LINEAR_STOPPING_ACCELERATION = MetersPerSecondPerSecond.of(10); - public static final LinearAcceleration MAX_ELEVATOR_UP_ACCEL = MetersPerSecondPerSecond.of(2); - - public static final LinearVelocity TIPPING_LIMITER_THRESHOLD = MetersPerSecond.of(3); - public static final String SUBSYSTEM_NAME = "Drive"; // For zeroing on robot init diff --git a/src/main/java/frc/robot/Subsystems/Drive/DriveIO.java b/src/main/java/frc/robot/Subsystems/Drive/DriveIO.java index 22eca35..8afb66a 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/DriveIO.java +++ b/src/main/java/frc/robot/Subsystems/Drive/DriveIO.java @@ -10,14 +10,9 @@ import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import frc.robot.Subsystems.Drive.TunerConstants.TunerSwerveDrivetrain; -import org.littletonrobotics.junction.AutoLog; public interface DriveIO { - /** - * Represents the inputs for the DriveIO. - */ - @AutoLog - public class DriveIOInputs { + public class DriveIOOutputs { ChassisSpeeds speeds = new ChassisSpeeds(); SwerveModuleState[] setPoints = new SwerveModuleState[4]; @@ -29,42 +24,17 @@ public class DriveIOInputs { double gyroAngleDeg = 0; } - /** - * Updates the inputs for the DriveIO. - * - * @param inputs The DriveIOInputs object containing the updated inputs. - */ - public default void updateInputs(DriveIOInputs inputs) {} + public default void logOutputs(DriveIOOutputs outputs) {} - /** - * Gets the SwerveDrivetrain associated with the DriveIO. - * - * @return The SwerveDrivetrain object. - */ public default TunerSwerveDrivetrain getDrive() { return null; } - /** - * Resets the gyro to zero. - */ public default void zeroGyro() {} - /** - * Sets the control for the SwerveRequest. - * - * @param request The SwerveRequest object containing the control information. - */ public default void setControl(SwerveRequest request) {} - /** - * Adds a vision measurement to the DriveIO. - * - * @param pose The Pose2d object representing the vision measurement. - * @param timestamp The timestamp of the vision measurement. - * @param standardDeviation The standard deviation of the vision measurement. - */ - public default void addVisionMeasurement(Pose2d pose, double timestamp, Matrix standardDeviation) {} + public default void addVisionMeasurement(Pose2d pose, double timestamp, Matrix standardDeviaton) {} public TalonFX[] getDriveMotors(); diff --git a/src/main/java/frc/robot/Subsystems/Drive/DriveIOReal.java b/src/main/java/frc/robot/Subsystems/Drive/DriveIOReal.java index ab9f7ed..455383f 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/DriveIOReal.java +++ b/src/main/java/frc/robot/Subsystems/Drive/DriveIOReal.java @@ -11,71 +11,43 @@ import edu.wpi.first.math.numbers.N3; import frc.robot.Subsystems.Drive.TunerConstants.TunerSwerveDrivetrain; -/** - * This class implements the DriveIO interface and provides the real implementation for controlling the drivetrain. - */ public class DriveIOReal implements DriveIO { - public DriveIOInputs inputs = new DriveIOInputs(); + public DriveIOOutputs outputs = new DriveIOOutputs(); private final TunerSwerveDrivetrain drivetrain = new TunerSwerveDrivetrain(DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight); - /** - * Updates the inputs for the drivetrain based on the current state of the SwerveDrivetrain. - * @param inputs The DriveIOInputs object to update. - */ @Override - public void updateInputs(DriveIOInputs inputs) { - inputs.speeds = drivetrain.getState().Speeds; - inputs.setPoints = drivetrain.getState().ModuleTargets; - inputs.odometryFrequency = drivetrain.getOdometryFrequency(); - inputs.timestamp = drivetrain.getState().Timestamp; - inputs.failedDataAquisitions = drivetrain.getState().FailedDaqs; - inputs.robotAngleDeg = drivetrain.getState().Pose.getRotation().getDegrees(); - inputs.fullRobotRotation = drivetrain.getRotation3d(); - inputs.gyroAngleDeg = drivetrain.getPigeon2().getYaw().getValueAsDouble(); + public void logOutputs(DriveIOOutputs outputs) { + outputs.speeds = drivetrain.getState().Speeds; + outputs.setPoints = drivetrain.getState().ModuleTargets; + outputs.odometryFrequency = drivetrain.getOdometryFrequency(); + outputs.timestamp = drivetrain.getState().Timestamp; + outputs.failedDataAquisitions = drivetrain.getState().FailedDaqs; + outputs.robotAngleDeg = drivetrain.getState().Pose.getRotation().getDegrees(); + outputs.fullRobotRotation = drivetrain.getRotation3d(); + outputs.gyroAngleDeg = drivetrain.getPigeon2().getYaw().getValueAsDouble(); } - /** - * Gets the SwerveDrivetrain object. - * @return The SwerveDrivetrain object. - */ @Override public TunerSwerveDrivetrain getDrive() { return drivetrain; } - /** - * Resets the gyro angle to zero. - */ @Override public void zeroGyro() { drivetrain.resetRotation(new Rotation2d()); } - /** - * Sets the control mode and target for the SwerveDrivetrain. - * @param request The SwerveRequest object containing the control mode and target. - */ @Override public void setControl(SwerveRequest request) { drivetrain.setControl(request); } - /** - * Adds a vision measurement to the SwerveDrivetrain for localization. - * @param pose The Pose2d object representing the measured pose. - * @param timestamp The timestamp of the measurement. - * @param standardDeviation The standard deviation of the measurement. - */ @Override - public void addVisionMeasurement(Pose2d pose, double timestamp, Matrix standardDeviation) { - drivetrain.addVisionMeasurement(pose, timestamp, standardDeviation); + public void addVisionMeasurement(Pose2d pose, double timestamp, Matrix standardDeviaton) { + drivetrain.addVisionMeasurement(pose, timestamp, standardDeviaton); } - /** - * Gets the drive motors for the SwerveDrivetrain. - * @return An array of TalonFX objects representing the drive motors. - */ @Override public TalonFX[] getDriveMotors() { TalonFX[] motors = new TalonFX[drivetrain.getModules().length]; diff --git a/src/main/java/frc/robot/Subsystems/Drive/DriveIOSim.java b/src/main/java/frc/robot/Subsystems/Drive/DriveIOSim.java index f6c40cd..83bc603 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/DriveIOSim.java +++ b/src/main/java/frc/robot/Subsystems/Drive/DriveIOSim.java @@ -6,19 +6,11 @@ import edu.wpi.first.wpilibj.Notifier; import edu.wpi.first.wpilibj.RobotController; -/** - * This class represents the simulated input/output for the drive subsystem. - * It extends the DriveIOReal class and provides additional functionality for simulation. - */ public class DriveIOSim extends DriveIOReal { private double lastSimTime; private Notifier simNotifier; - /** - * Constructs a new DriveIOSim object. - * It initializes the superclass and starts the simulation thread. - */ public DriveIOSim() { startSimThread(); } diff --git a/src/main/java/frc/robot/Subsystems/Drive/DriveStates.java b/src/main/java/frc/robot/Subsystems/Drive/DriveStates.java index a141ff8..163708f 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/DriveStates.java +++ b/src/main/java/frc/robot/Subsystems/Drive/DriveStates.java @@ -7,51 +7,33 @@ import org.team7525.subsystem.SubsystemStates; -/** - * An enumeration representing different drive states for a robot's drive subsystem. - */ public enum DriveStates implements SubsystemStates { - /** - * The robot's drive is in field-relative mode. - */ FIELD_RELATIVE("Field Relative", () -> { - Drive.getInstance().driveFieldRelative(-DRIVER_CONTROLLER.getLeftY() * kSpeedAt12Volts.in(MetersPerSecond) * 0.4, -DRIVER_CONTROLLER.getLeftX() * kSpeedAt12Volts.in(MetersPerSecond) * 0.4, -DRIVER_CONTROLLER.getRightX() * ANGULAR_VELOCITY_LIMIT.in(RadiansPerSecond) * 0.1 * 0.5); + double forward = -applyDeadband(DRIVER_CONTROLLER.getLeftY()) * kSpeedAt12Volts.in(MetersPerSecond); + double strafe = -applyDeadband(DRIVER_CONTROLLER.getLeftX()) * kSpeedAt12Volts.in(MetersPerSecond); + double rot = -applyDeadband(DRIVER_CONTROLLER.getRightX()) * ANGULAR_VELOCITY_LIMIT.in(RadiansPerSecond) * 0.1; + Drive.getInstance().driveFieldRelative(forward, strafe, rot); }), - - /** - * The robot's drive is in robot-relative mode. - */ ROBOT_RELATIVE("Robot Relative", () -> { - Drive.getInstance().driveRobotRelative(DRIVER_CONTROLLER.getLeftY() * kSpeedAt12Volts.in(MetersPerSecond), DRIVER_CONTROLLER.getLeftX() * kSpeedAt12Volts.in(MetersPerSecond), DRIVER_CONTROLLER.getRightX() * ANGULAR_VELOCITY_LIMIT.in(RadiansPerSecond)); + double forward = applyDeadband(DRIVER_CONTROLLER.getLeftY()) * kSpeedAt12Volts.in(MetersPerSecond); + double strafe = applyDeadband(DRIVER_CONTROLLER.getLeftX()) * kSpeedAt12Volts.in(MetersPerSecond); + double rot = applyDeadband(DRIVER_CONTROLLER.getRightX()) * ANGULAR_VELOCITY_LIMIT.in(RadiansPerSecond); + Drive.getInstance().driveRobotRelative(forward, strafe, rot); }); private String stateString; private Runnable driveControl; - /** - * Constructs a DriveStates enum value with the specified state string and field-relative flag. - * - * @param stateString the string representation of the drive state - * @param Runnable runnable that gets called to drive the robot - */ DriveStates(String stateString, Runnable driveControl) { this.stateString = stateString; this.driveControl = driveControl; } - /** - * Returns the string representation of the drive state. - * - * @return the string representation of the drive state - */ @Override public String getStateString() { return stateString; } - /** - * Drives the robot in the current state. - */ public void driveRobot() { driveControl.run(); } diff --git a/src/main/java/frc/robot/Subsystems/Drive/TunerConstants.java b/src/main/java/frc/robot/Subsystems/Drive/TunerConstants.java index 0b8528e..036369f 100644 --- a/src/main/java/frc/robot/Subsystems/Drive/TunerConstants.java +++ b/src/main/java/frc/robot/Subsystems/Drive/TunerConstants.java @@ -80,7 +80,7 @@ public class TunerConstants { private static final boolean kInvertLeftSide = true; private static final boolean kInvertRightSide = false; - private static final int kPigeonId = 39; + private static final int kPigeonId = 45; // These are only used for simulation private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01); diff --git a/src/main/java/frc/robot/Subsystems/Hopper/HopperConstants.java b/src/main/java/frc/robot/Subsystems/Hopper/HopperConstants.java index 7615fe1..4e8b8ff 100644 --- a/src/main/java/frc/robot/Subsystems/Hopper/HopperConstants.java +++ b/src/main/java/frc/robot/Subsystems/Hopper/HopperConstants.java @@ -10,8 +10,8 @@ public class HopperConstants { public static final String SUBSYSTEM_NAME = "Hopper"; - public static final int SPINDEXER_MOTOR_ID = 0; - public static final int KICKER_MOTOR_ID = 1; + public static final int SPINDEXER_MOTOR_ID = 33; + public static final int KICKER_MOTOR_ID = 34; public static class Sim { diff --git a/src/main/java/frc/robot/Subsystems/Manager/Manager.java b/src/main/java/frc/robot/Subsystems/Manager/Manager.java new file mode 100644 index 0000000..d97f54c --- /dev/null +++ b/src/main/java/frc/robot/Subsystems/Manager/Manager.java @@ -0,0 +1,129 @@ +package frc.robot.Subsystems.Manager; + +import static frc.robot.GlobalConstants.Controllers.DRIVER_CONTROLLER; +import static frc.robot.GlobalConstants.Controllers.OPERATOR_CONTROLLER; +import static frc.robot.Subsystems.Manager.ManagerConstants.*; + +import edu.wpi.first.wpilibj.DriverStation; +import frc.robot.Subsystems.Climber.Climber; +import frc.robot.Subsystems.Drive.Drive; +import frc.robot.Subsystems.Hopper.Hopper; +import frc.robot.Subsystems.Intake.Intake; +import frc.robot.Subsystems.Shooter.Shooter; +import frc.robot.Subsystems.Vision.Vision; +import org.littletonrobotics.junction.Logger; +import org.team7525.misc.Tracer; +import org.team7525.subsystem.Subsystem; + +public class Manager extends Subsystem { + + private static Manager instance; + private Drive drive; + private Shooter shooter; + private Hopper hopper; + private Intake intake; + private Climber climber; + private Vision vision; + + public static Manager getInstance() { + if (instance == null) { + new Manager(); + } + return instance; + } + + private Manager() { + super(SUBSYSTEM_NAME, ManagerStates.IDLE); + instance = this; + drive = Drive.getInstance(); + shooter = Shooter.getInstance(); + hopper = Hopper.getInstance(); + intake = Intake.getInstance(); + climber = Climber.getInstance(); + vision = Vision.getInstance(); + + // IDLE <---> EXTENDED_IDLE + addTrigger(ManagerStates.IDLE, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getRightBumperButtonPressed); + addTrigger(ManagerStates.EXTENDED_IDLE, ManagerStates.IDLE, DRIVER_CONTROLLER::getRightBumperButtonPressed); + + // IDLE/EXTENDED_IDLE --> INTAKING + addTrigger(ManagerStates.IDLE, ManagerStates.INTAKING, DRIVER_CONTROLLER::getXButtonPressed); + addTrigger(ManagerStates.EXTENDED_IDLE, ManagerStates.INTAKING, DRIVER_CONTROLLER::getXButtonPressed); + + // INTAKING --> EXTENDED_IDLE + addTrigger(ManagerStates.INTAKING, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getXButtonPressed); + + // IDLE/EXTENDED_IDLE --> WINDING_UP + addTrigger(ManagerStates.IDLE, ManagerStates.WINDING_UP, DRIVER_CONTROLLER::getYButtonPressed); + addTrigger(ManagerStates.EXTENDED_IDLE, ManagerStates.WINDING_UP, DRIVER_CONTROLLER::getYButtonPressed); + addTrigger(ManagerStates.IDLE, ManagerStates.WINDING_UP_FIXED_SHOT, DRIVER_CONTROLLER::getBButtonPressed); + addTrigger(ManagerStates.EXTENDED_IDLE, ManagerStates.WINDING_UP_FIXED_SHOT, DRIVER_CONTROLLER::getBButtonPressed); + + // INTAKING --> WINDING_UP + addTrigger(ManagerStates.INTAKING, ManagerStates.WINDING_UP, DRIVER_CONTROLLER::getYButtonPressed); + addTrigger(ManagerStates.INTAKING, ManagerStates.WINDING_UP_FIXED_SHOT, DRIVER_CONTROLLER::getBButtonPressed); + + // WINDING_UP --> SHOOTING_HUB/SHOOTING_FIXED/SHOOTING_ALLIANCE + addTrigger(ManagerStates.WINDING_UP, ManagerStates.SHOOTING_HUB, () -> shooter.readyToShoot() && drive.isAtAllianceShootingPosition()); + addTrigger(ManagerStates.WINDING_UP_FIXED_SHOT, ManagerStates.SHOOTING_FIXED, DRIVER_CONTROLLER::getBButtonPressed); + addTrigger(ManagerStates.WINDING_UP, ManagerStates.SHUTTLING, () -> shooter.readyToShoot() && !drive.isAtAllianceShootingPosition()); + + // SHOOTING --> EXTENDED_IDLE + addTrigger(ManagerStates.SHOOTING_HUB, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getYButtonPressed); + addTrigger(ManagerStates.SHUTTLING, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getYButtonPressed); + addTrigger(ManagerStates.SHOOTING_FIXED, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getBButtonPressed); + + // IDLE <---> EXTENDING_CLIMBER + addTrigger(ManagerStates.IDLE, ManagerStates.EXTENDING_CLIMBER, OPERATOR_CONTROLLER::getRightBumperButtonPressed); + + // EXTENDING_CLIMBER <---> RETRACTING_CLIMBER + addTrigger(ManagerStates.EXTENDING_CLIMBER, ManagerStates.RETRACTING_CLIMBER, OPERATOR_CONTROLLER::getRightBumperButtonPressed); + addTrigger(ManagerStates.RETRACTING_CLIMBER, ManagerStates.EXTENDING_CLIMBER, OPERATOR_CONTROLLER::getLeftBumperButtonPressed); + addTrigger(ManagerStates.EXTENDING_CLIMBER, ManagerStates.IDLE, OPERATOR_CONTROLLER::getLeftBumperButtonPressed); + } + + @Override + public void runState() { + var allianceOpt = DriverStation.getAlliance(); + if (allianceOpt.isEmpty()) { + // Alliance not yet known (early init); record as UNKNOWN instead of calling get(). + Logger.recordOutput(SUBSYSTEM_NAME + "/ALLIANCE COLOR", "UNKNOWN"); + } else if (allianceOpt.get() == DriverStation.Alliance.Red) { + Logger.recordOutput(SUBSYSTEM_NAME + "/ALLIANCE COLOR", "RED"); + } else { + Logger.recordOutput(SUBSYSTEM_NAME + "/ALLIANCE COLOR", "BLUE"); + } + + Logger.recordOutput(SUBSYSTEM_NAME + "/STATE", getState().getStateString()); + Logger.recordOutput(SUBSYSTEM_NAME + "/InAllianceShootingPosition", drive.isAtAllianceShootingPosition()); + Logger.recordOutput(SUBSYSTEM_NAME + "/STATE TIME", getStateTime()); + Logger.recordOutput(SUBSYSTEM_NAME + "/HUB ACTIVE", isHubActive()); + + // Set subsystem states + shooter.setState(getState().getShooterState()); + hopper.setState(getState().getHopperState()); + intake.setState(getState().getIntakeState()); + climber.setState(getState().getClimberState()); + + Tracer.traceFunc("ShooterPeriodic", shooter::periodic); // SHould these be used with Tracer? idk what that does fr + Tracer.traceFunc("HopperPeriodic", hopper::periodic); + Tracer.traceFunc("IntakePeriodic", intake::periodic); + Tracer.traceFunc("ClimberPeriodic", climber::periodic); + Tracer.traceFunc("DrivePeriodic", drive::periodic); + Tracer.traceFunc("VisionPeriodic", vision::periodic); + // Emergency stop to IDLE + if (DRIVER_CONTROLLER.getStartButtonPressed()) { + setState(ManagerStates.IDLE); + } + } + + public boolean isHubActive() { + return true; // TODO: implement this idk how + } + + @Override + public void periodic() { + super.periodic(); + WiltingRoseControllerUtility.resetWiltingRoseControllers(); + } +} diff --git a/src/main/java/frc/robot/Subsystems/Manager/ManagerConstants.java b/src/main/java/frc/robot/Subsystems/Manager/ManagerConstants.java new file mode 100644 index 0000000..6ff69e6 --- /dev/null +++ b/src/main/java/frc/robot/Subsystems/Manager/ManagerConstants.java @@ -0,0 +1,6 @@ +package frc.robot.Subsystems.Manager; + +public class ManagerConstants { + + public static final String SUBSYSTEM_NAME = "Manager"; +} diff --git a/src/main/java/frc/robot/Subsystems/Manager/ManagerStates.java b/src/main/java/frc/robot/Subsystems/Manager/ManagerStates.java new file mode 100644 index 0000000..255c916 --- /dev/null +++ b/src/main/java/frc/robot/Subsystems/Manager/ManagerStates.java @@ -0,0 +1,61 @@ +package frc.robot.Subsystems.Manager; + +import frc.robot.Subsystems.Climber.ClimberStates; +import frc.robot.Subsystems.Drive.Drive; +import frc.robot.Subsystems.Hopper.HopperStates; +import frc.robot.Subsystems.Intake.IntakeStates; +import frc.robot.Subsystems.Shooter.ShooterStates; +import org.team7525.subsystem.SubsystemStates; + +public enum ManagerStates implements SubsystemStates { + IDLE("IDLE", IntakeStates.IN, HopperStates.IDLE, ShooterStates.IDLE, ClimberStates.IDLE), + EXTENDED_IDLE("EXTENDED_IDLE", IntakeStates.OUT, HopperStates.IDLE, ShooterStates.IDLE, ClimberStates.IDLE), + INTAKING("INTAKING", IntakeStates.INTAKE, HopperStates.SPINDEXING, ShooterStates.STANDBY, ClimberStates.IDLE), + WINDING_UP("WINDING_UP", IntakeStates.IN, HopperStates.IDLE, null, ClimberStates.IDLE), + WINDING_UP_FIXED_SHOT("WINDING_UP_FIXED_SHOT", IntakeStates.IN, HopperStates.IDLE, ShooterStates.SHOOT_FIXED, ClimberStates.IDLE), + SHUTTLING("SHUTTLING", IntakeStates.IN, HopperStates.SPINDEXING, ShooterStates.SHOOT_ALLIANCE, ClimberStates.IDLE), + SHOOTING_HUB("SHOOTING_HUB", IntakeStates.IN, HopperStates.SPINDEXING, ShooterStates.SHOOT_HUB, ClimberStates.IDLE), + SHOOTING_FIXED("SHOOTING_FIXED", IntakeStates.IN, HopperStates.SPINDEXING, ShooterStates.SHOOT_FIXED, ClimberStates.IDLE), + EXTENDING_CLIMBER("EXTENDING_CLIMBER", IntakeStates.IN, HopperStates.IDLE, ShooterStates.IDLE, ClimberStates.EXTEND), + RETRACTING_CLIMBER("RETRACTING_CLIMBER", IntakeStates.IN, HopperStates.IDLE, ShooterStates.IDLE, ClimberStates.RETRACT); + + private final String stateString; + private final IntakeStates intakeState; + private final HopperStates hopperState; + private final ShooterStates shooterState; + private final ClimberStates climberState; + + ManagerStates(String stateString, IntakeStates intakeState, HopperStates hopperState, ShooterStates shooterState, ClimberStates climberState) { + this.stateString = stateString; + this.intakeState = intakeState; + this.hopperState = hopperState; + this.shooterState = shooterState; + this.climberState = climberState; + } + + @Override + public String getStateString() { + return stateString; + } + + public IntakeStates getIntakeState() { + return intakeState; + } + + public HopperStates getHopperState() { + return hopperState; + } + + public ShooterStates getShooterState() { + // Could be in shooter but would lead to wierd states i think + // shhoter doesn't change between winding up and shooting only hopper does + if (this == WINDING_UP && shooterState == null) { + return Drive.getInstance().isAtAllianceShootingPosition() ? ShooterStates.SHOOT_ALLIANCE : ShooterStates.SHOOT_HUB; + } + return shooterState; + } + + public ClimberStates getClimberState() { + return climberState; + } +} diff --git a/src/main/java/frc/robot/Subsystems/Manager/WiltingRoseControllerUtility.java b/src/main/java/frc/robot/Subsystems/Manager/WiltingRoseControllerUtility.java new file mode 100644 index 0000000..9a4c1f2 --- /dev/null +++ b/src/main/java/frc/robot/Subsystems/Manager/WiltingRoseControllerUtility.java @@ -0,0 +1,29 @@ +package frc.robot.Subsystems.Manager; + +import static frc.robot.GlobalConstants.Controllers.*; + +class WiltingRoseControllerUtility { + + public static void resetWiltingRoseControllers() { + // Read each controller press once (this clears the internal "pressed" cache). DRIVER_CONTROLLER.getAButtonPressed(); + DRIVER_CONTROLLER.getBButtonPressed(); + DRIVER_CONTROLLER.getXButtonPressed(); + DRIVER_CONTROLLER.getYButtonPressed(); + DRIVER_CONTROLLER.getBackButtonPressed(); + DRIVER_CONTROLLER.getStartButtonPressed(); + DRIVER_CONTROLLER.getLeftBumperButtonPressed(); + DRIVER_CONTROLLER.getRightBumperButtonPressed(); + DRIVER_CONTROLLER.getLeftStickButtonPressed(); + DRIVER_CONTROLLER.getRightStickButtonPressed(); + OPERATOR_CONTROLLER.getAButtonPressed(); + OPERATOR_CONTROLLER.getBButtonPressed(); + OPERATOR_CONTROLLER.getXButtonPressed(); + OPERATOR_CONTROLLER.getYButtonPressed(); + OPERATOR_CONTROLLER.getBackButtonPressed(); + OPERATOR_CONTROLLER.getStartButtonPressed(); + OPERATOR_CONTROLLER.getLeftBumperButtonPressed(); + OPERATOR_CONTROLLER.getRightBumperButtonPressed(); + OPERATOR_CONTROLLER.getLeftStickButtonPressed(); + OPERATOR_CONTROLLER.getRightStickButtonPressed(); + } +} diff --git a/src/main/java/frc/robot/Subsystems/Shooter/Shooter.java b/src/main/java/frc/robot/Subsystems/Shooter/Shooter.java index 934a166..27ae044 100644 --- a/src/main/java/frc/robot/Subsystems/Shooter/Shooter.java +++ b/src/main/java/frc/robot/Subsystems/Shooter/Shooter.java @@ -1,5 +1,7 @@ package frc.robot.Subsystems.Shooter; +import static edu.wpi.first.units.Units.Degrees; +import static edu.wpi.first.units.Units.RotationsPerSecond; import static frc.robot.Subsystems.Shooter.ShooterConstants.*; import frc.robot.GlobalConstants; @@ -25,7 +27,7 @@ public static Shooter getInstance() { } private Shooter(ShooterIO io) { - super(SUBSYSTEM_NAME, ShooterStates.OFF); + super(SUBSYSTEM_NAME, ShooterStates.IDLE); this.io = io; outputs = new ShooterIOOutputs(); } @@ -36,11 +38,11 @@ public void runState() { io.setWheelVelocity(getState().getWheelVelocity()); io.logOutputs(outputs); - Logger.recordOutput(SUBSYSTEM_NAME + "/LeftWheelVelocity", outputs.leftWheelVelocity); - Logger.recordOutput(SUBSYSTEM_NAME + "/RightWheelVelocity", outputs.rightWheelVelocity); - Logger.recordOutput(SUBSYSTEM_NAME + "/WheelSetpoint", outputs.wheelSetpoint); - Logger.recordOutput(SUBSYSTEM_NAME + "/HoodAngle", outputs.hoodAngle); - Logger.recordOutput(SUBSYSTEM_NAME + "/HoodSetpoint", outputs.hoodSetpoint); + Logger.recordOutput(SUBSYSTEM_NAME + "/LeftWheelVelocity", outputs.leftWheelVelocity.in(RotationsPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/RightWheelVelocity", outputs.rightWheelVelocity.in(RotationsPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/WheelSetpoint", outputs.wheelSetpoint.in(RotationsPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/HoodAngle", outputs.hoodAngle.in(Degrees)); + Logger.recordOutput(SUBSYSTEM_NAME + "/HoodSetpoint", outputs.hoodSetpoint.in(Degrees)); Logger.recordOutput(SUBSYSTEM_NAME + "/state", getState().getStateString()); Logger.recordOutput(SUBSYSTEM_NAME + "/ReadyToShoot", readyToShoot()); } diff --git a/src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java b/src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java index 68d568a..7797b97 100644 --- a/src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java +++ b/src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java @@ -14,9 +14,15 @@ public final class ShooterConstants { public static final String SUBSYSTEM_NAME = "Shooter"; + // Preset positions + public static final double HOOD_MIN_ANGLE_RADS = 0.0; // TODO: get real value + public static final double HOOD_MAX_ANGLE_RADS = Math.toRadians(60); // TODO: get real value public static final Angle FIXED_SHOT_ANGLE = Degrees.of(45); //TODO: get good value - public static final AngularVelocity FIXED_SHOT_SPEED = RotationsPerSecond.of(1000); //TODO: get good value + public static final AngularVelocity FIXED_SHOT_SPEED = RotationsPerSecond.of(150); //TODO: get good value + + public static final Angle STANDBY_ANGLE = Degrees.of(45); //TODO: get good value + public static final AngularVelocity STANDBY_SPEED = RotationsPerSecond.of(500); //TODO: get good value // Numerical constants (moved from magic literals) public static final double SOLVER_EPSILON = 1e-6; @@ -27,35 +33,35 @@ public final class ShooterConstants { public static final double HOOD_ANGLE_TOLERANCE_DEGREES = 0.01; // degrees // Simulation / physical defaults - public static final double FLYWHEEL_MOI = 0.5; - public static final double FLYWHEEL_GEARING = 1.0; - public static final double HOOD_MOI = 0.2; + public static final double FLYWHEEL_MOI = 0.00117056; // Roughly accurate for flywheel + public static final double FLYWHEEL_GEARING = 1.0; // Also roughly accurate + public static final double HOOD_MOI = 0.0001; public static final double HOOD_GEARING = 1.0; - public static final double HOOD_ARM_LENGTH_METERS = 1.0; + public static final double HOOD_ARM_LENGTH_METERS = 0.2; // State defaults public static final AngularVelocity REVERSE_WHEEL_SPEED = RotationsPerSecond.of(-100); - public static final int LEFT_SHOOTER_MOTOR_ID = 10; - public static final int RIGHT_SHOOTER_MOTOR_ID = 11; - public static final int HOOD_MOTOR_ID = 12; + public static final int LEFT_SHOOTER_MOTOR_ID = 37; + public static final int RIGHT_SHOOTER_MOTOR_ID = 38; + public static final int HOOD_MOTOR_ID = 39; public static final Supplier HOOD_PID = () -> switch (GlobalConstants.ROBOT_MODE) { case REAL -> new PIDController(1, 0, 0); - case SIM -> new PIDController(0.05, 0, 0); + case SIM -> new PIDController(0.04, 0, 0.001); // Tuned in sim case TESTING -> new PIDController(1, 0, 0); }; //TODO: tune public static final Supplier WHEEL_PID = () -> switch (GlobalConstants.ROBOT_MODE) { case REAL -> new PIDController(0.1, 0, 0); - case SIM -> new PIDController(0.01, 0, 0); + case SIM -> new PIDController(0.0077, 0, 0.00013); case TESTING -> new PIDController(0.1, 0, 0); }; //TODO: tune public static final Supplier WHEEL_FEEDFORWARD = () -> switch (GlobalConstants.ROBOT_MODE) { case REAL -> new SimpleMotorFeedforward(0.1, 0.01, 0.001); - case SIM -> new SimpleMotorFeedforward(0.05, 0.005, 0.0005); + case SIM -> new SimpleMotorFeedforward(0.11, 0.1, 0.0); case TESTING -> new SimpleMotorFeedforward(0.1, 0.01, 0.001); }; //TODO: tune diff --git a/src/main/java/frc/robot/Subsystems/Shooter/ShooterIOSim.java b/src/main/java/frc/robot/Subsystems/Shooter/ShooterIOSim.java index e7a10bd..d2ac421 100644 --- a/src/main/java/frc/robot/Subsystems/Shooter/ShooterIOSim.java +++ b/src/main/java/frc/robot/Subsystems/Shooter/ShooterIOSim.java @@ -1,20 +1,24 @@ package frc.robot.Subsystems.Shooter; import static edu.wpi.first.units.Units.Degrees; +import static edu.wpi.first.units.Units.Radians; +import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RotationsPerSecond; +import static frc.robot.GlobalConstants.VOLTS; import static frc.robot.Subsystems.Shooter.ShooterConstants.*; import com.ctre.phoenix6.controls.Follower; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.MotorAlignmentValue; import com.ctre.phoenix6.sim.TalonFXSimState; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj.simulation.FlywheelSim; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.GlobalConstants; public class ShooterIOSim extends ShooterIOReal { @@ -22,21 +26,15 @@ public class ShooterIOSim extends ShooterIOReal { private TalonFXSimState leftMotorSim; private TalonFXSimState rightMotorSim; private TalonFXSimState hoodMotorSim; - private SimpleMotorFeedforward wheelFeedforward; private FlywheelSim wheelSim; private SingleJointedArmSim hoodSim; public ShooterIOSim() { - leftMotor = new TalonFX(LEFT_SHOOTER_MOTOR_ID); - rightMotor = new TalonFX(RIGHT_SHOOTER_MOTOR_ID); + super(); hoodMotor = new TalonFX(HOOD_MOTOR_ID); rightMotor.setControl(new Follower(leftMotor.getDeviceID(), MotorAlignmentValue.Aligned)); // Might need to be inverted - hoodPID = HOOD_PID.get(); - wheelPID = WHEEL_PID.get(); - wheelFeedforward = WHEEL_FEEDFORWARD.get(); - - leftMotorSim = new TalonFXSimState(leftMotor); rightMotorSim = new TalonFXSimState(rightMotor); + leftMotorSim = new TalonFXSimState(leftMotor); hoodMotorSim = new TalonFXSimState(hoodMotor); wheelSim = new FlywheelSim( @@ -54,42 +52,47 @@ public ShooterIOSim() { HOOD_GEARING // Gearing ), DCMotor.getFalcon500(1), - HOOD_ARM_LENGTH_METERS, // Arm length - 0, - 0, - 0, - true, - 0 + HOOD_GEARING, + HOOD_ARM_LENGTH_METERS, + HOOD_MIN_ANGLE_RADS, + HOOD_MAX_ANGLE_RADS, + false, // this be ragebait + HOOD_MIN_ANGLE_RADS ); } @Override public void logOutputs(ShooterIOOutputs outputs) { + // Sim update + leftMotorSim.setRotorVelocity(Units.radiansToRotations(wheelSim.getAngularVelocityRadPerSec())); + rightMotorSim.setRotorVelocity(Units.radiansToRotations(wheelSim.getAngularVelocityRadPerSec())); + hoodMotorSim.setRawRotorPosition(Units.radiansToRotations(hoodSim.getAngleRads())); + hoodMotorSim.setSupplyVoltage(VOLTS); + hoodMotorSim.setRotorVelocity(Units.radiansToRotations(hoodSim.getVelocityRadPerSec())); + wheelSim.update(GlobalConstants.SIMULATION_PERIOD); + hoodSim.update(GlobalConstants.SIMULATION_PERIOD); + outputs.leftWheelVelocity = leftMotor.getVelocity().getValue(); outputs.rightWheelVelocity = rightMotor.getVelocity().getValue(); outputs.wheelSetpoint = wheelSetpoint; - outputs.hoodAngle = hoodMotor.getPosition().getValue(); + outputs.hoodAngle = Radians.of(hoodSim.getAngleRads()); outputs.hoodSetpoint = hoodSetpoint; - // Sim update - wheelSim.update(GlobalConstants.SIMULATION_PERIOD); - hoodSim.update(GlobalConstants.SIMULATION_PERIOD); - leftMotorSim.setRotorVelocity(wheelSim.getAngularVelocityRadPerSec()); - rightMotorSim.setRotorVelocity(wheelSim.getAngularVelocityRadPerSec()); - hoodMotorSim.setRawRotorPosition(hoodSim.getAngleRads()); - hoodMotorSim.setRotorVelocity(hoodSim.getVelocityRadPerSec()); // Throw some stuff here for 3D sim later } @Override public void setWheelVelocity(AngularVelocity velocity) { wheelSetpoint = velocity; - leftMotor.set(wheelPID.calculate(leftMotor.getVelocity().getValue().in(RotationsPerSecond), wheelSetpoint.in(RotationsPerSecond)) + wheelFeedforward.calculate(wheelSetpoint.in(RotationsPerSecond))); + SmartDashboard.putNumber("Wheel Setpoint (Radians per Second)", wheelSetpoint.in(RadiansPerSecond)); + wheelSim.setInputVoltage(VOLTS * (wheelPID.calculate(wheelSim.getAngularVelocityRadPerSec(), wheelSetpoint.in(RadiansPerSecond)) + wheelFeedforward.calculate(wheelSetpoint.in(RadiansPerSecond)))); } @Override public void setHoodAngle(Angle angle) { hoodSetpoint = angle; - hoodMotor.set(hoodPID.calculate(hoodMotor.getPosition().getValue().in(Degrees), hoodSetpoint.in(Degrees))); + double pid_calc = hoodPID.calculate(hoodSim.getAngleRads(), hoodSetpoint.in(Radians)); + SmartDashboard.putNumber("Hood PID Output", pid_calc); + hoodSim.setInputVoltage(pid_calc * VOLTS); } @Override diff --git a/src/main/java/frc/robot/Subsystems/Shooter/ShooterStates.java b/src/main/java/frc/robot/Subsystems/Shooter/ShooterStates.java index 8b1f01e..47548f9 100644 --- a/src/main/java/frc/robot/Subsystems/Shooter/ShooterStates.java +++ b/src/main/java/frc/robot/Subsystems/Shooter/ShooterStates.java @@ -13,7 +13,7 @@ import org.team7525.subsystem.SubsystemStates; public enum ShooterStates implements SubsystemStates { - OFF("IDLE", () -> Degrees.of(0), () -> RotationsPerSecond.of(0)), + IDLE("IDLE", () -> Degrees.of(0), () -> RotationsPerSecond.of(0)), REVERSE("REVERSE", () -> Degrees.of(0), () -> REVERSE_WHEEL_SPEED), // TODO: get good value // Use placeholder Pose2d and zero velocity for now; replace with real robot pose/velocity when available. SHOOT_HUB( @@ -27,7 +27,8 @@ public enum ShooterStates implements SubsystemStates { () -> ShooterMath.solveAllianceShot(new Pose2d(0.0, 0.0, new Rotation2d()), new Translation2d(0.0, 0.0)).map(sol -> sol.hoodAngle()).orElse(FIXED_SHOT_ANGLE), () -> ShooterMath.solveAllianceShot(new Pose2d(0.0, 0.0, new Rotation2d()), new Translation2d(0.0, 0.0)).map(sol -> sol.flywheelSpeed()).orElse(FIXED_SHOT_SPEED) ), - SHOOT_FIXED("SHOOT FIXED", () -> FIXED_SHOT_ANGLE, () -> FIXED_SHOT_SPEED); + SHOOT_FIXED("SHOOT FIXED", () -> FIXED_SHOT_ANGLE, () -> FIXED_SHOT_SPEED), + STANDBY("STANDBY", () -> STANDBY_ANGLE, () -> STANDBY_SPEED); private String stateString; private Supplier hoodAngleSupplier; diff --git a/src/main/java/frc/robot/Subsystems/Vision/Vision.java b/src/main/java/frc/robot/Subsystems/Vision/Vision.java index b3d597e..d0c9638 100644 --- a/src/main/java/frc/robot/Subsystems/Vision/Vision.java +++ b/src/main/java/frc/robot/Subsystems/Vision/Vision.java @@ -2,6 +2,7 @@ import static edu.wpi.first.units.Units.DegreesPerSecond; import static frc.robot.GlobalConstants.ROBOT_MODE; +import static frc.robot.Subsystems.Drive.DriveConstants.SUBSYSTEM_NAME; import static frc.robot.Subsystems.Vision.VisionConstants.*; import edu.wpi.first.math.Matrix; @@ -14,16 +15,17 @@ import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Robot; import frc.robot.Subsystems.Drive.Drive; import frc.robot.Subsystems.Vision.VisionIO.PoseObservation; import frc.robot.Subsystems.Vision.VisionIO.VisionIOOutputs; import java.util.LinkedList; import java.util.List; +import java.util.Set; import org.littletonrobotics.junction.Logger; public class Vision extends SubsystemBase { - // Akit my savior private final VisionIO[] io; private final VisionIOOutputs[] outputs; private final Alert[] disconnectedAlerts; @@ -33,15 +35,20 @@ public class Vision extends SubsystemBase { List allRobotPosesAccepted = new LinkedList<>(); List allRobotPosesRejected = new LinkedList<>(); + Set allianceHubTags = Robot.isRedAlliance ? RED_HUB_TAGS : BLUE_HUB_TAGS; + private static Vision instance; public static Vision getInstance() { if (instance == null) { instance = new Vision( switch (ROBOT_MODE) { - case REAL -> new VisionIO[] { new VisionIOPhotonVision(CAM_1_NAME, ROBOT_TO_CAM1), new VisionIOPhotonVision(CAM_2_NAME, ROBOT_TO_CAM2) }; - case SIM -> new VisionIO[] { new VisionIOPhotonVisionSim(CAM_1_NAME, ROBOT_TO_CAM1, Drive.getInstance()::getPose), new VisionIOPhotonVisionSim(CAM_2_NAME, ROBOT_TO_CAM2, Drive.getInstance()::getPose) }; - case TESTING -> new VisionIO[] { new VisionIOPhotonVision(CAM_2_NAME, ROBOT_TO_CAM2), new VisionIOPhotonVision(CAM_1_NAME, ROBOT_TO_CAM1) }; + case REAL -> new VisionIO[] { new VisionIOPhotonVision(FRONT_CAM_1_NAME, ROBOT_TO_FRONT_CAM_1), new VisionIOPhotonVision(FRONT_CAM_2_NAME, ROBOT_TO_FRONT_CAM_2) }; + case SIM -> new VisionIO[] { + new VisionIOPhotonVisionSim(FRONT_CAM_1_NAME, ROBOT_TO_FRONT_CAM_1, Drive.getInstance()::getPose), + // new VisionIOPhotonVisionSim(FRONT_CAM_2_NAME, ROBOT_TO_FRONT_CAM_2, Drive.getInstance()::getPose), + }; + case TESTING -> new VisionIO[] { new VisionIOPhotonVision(FRONT_CAM_1_NAME, ROBOT_TO_FRONT_CAM_1), new VisionIOPhotonVision(FRONT_CAM_2_NAME, ROBOT_TO_FRONT_CAM_2) }; } ); } @@ -51,7 +58,7 @@ public static Vision getInstance() { private Vision(VisionIO... io) { this.io = io; - // Initialize inputs + // Initialize outputs this.outputs = new VisionIOOutputs[io.length]; for (int i = 0; i < outputs.length; i++) { outputs[i] = new VisionIOOutputs(); @@ -76,12 +83,15 @@ public Rotation2d getTargetX(int cameraIndex) { @Override public void periodic() { + allianceHubTags = Robot.isRedAlliance ? RED_HUB_TAGS : BLUE_HUB_TAGS; + for (int i = 0; i < io.length; i++) { io[i].logOutputs(outputs[i]); - Logger.recordOutput("Vision/Camera" + Integer.toString(i) + "/Connected", outputs[i].connected); - Logger.recordOutput("Vision/Camera" + Integer.toString(i) + "/LatestTarget", outputs[i].latestTargetObservation); - Logger.recordOutput("Vision/Camera" + Integer.toString(i) + "/PoseObservations", outputs[i].poseObservations); - Logger.recordOutput("Vision/Camera" + Integer.toString(i) + "/TagIds", outputs[i].tagIds); + Logger.recordOutput(SUBSYSTEM_NAME + "/Camera " + Integer.toString(i) + "/Connected", outputs[i].connected); + Logger.recordOutput(SUBSYSTEM_NAME + "/Camera " + Integer.toString(i) + "/Latest Target X Deg", outputs[i].latestTargetObservation.tx().getDegrees()); + Logger.recordOutput(SUBSYSTEM_NAME + "/Camera " + Integer.toString(i) + "/Latest Target Y Deg", outputs[i].latestTargetObservation.ty().getDegrees()); + Logger.recordOutput(SUBSYSTEM_NAME + "/Camera " + Integer.toString(i) + "/Pose Observations Count", outputs[i].poseObservations.length); + Logger.recordOutput(SUBSYSTEM_NAME + "/Camera " + Integer.toString(i) + "/Tag IDs", outputs[i].tagIds); } // Initialize logging values @@ -139,19 +149,6 @@ private void processVision() { // Skip if rejected if (rejectPose) continue; - // Calculate standard deviations - // double stdDevFactor = Math.pow(observation.averageTagDistance(), 2.0) / observation.tagCount(); - // double linearStdDev = linearStdDevBaseline * stdDevFactor; - // double angularStdDev = angularStdDevBaseline * stdDevFactor; - // if (observation.type() == PoseObservationType.MEGATAG_2) { - // linearStdDev *= linearStdDevMegatag2Factor; - // angularStdDev *= angularStdDevMegatag2Factor; - // } - // if (cameraIndex < cameraStdDevFactors.length) { - // linearStdDev *= cameraStdDevFactors[cameraIndex]; - // angularStdDev *= cameraStdDevFactors[cameraIndex]; - // } - //254 standard dev Matrix visionStandardDev = calculateStandardDev(observation); @@ -159,7 +156,7 @@ private void processVision() { Drive.getInstance().addVisionMeasurement(observation.pose().toPose2d(), observation.timestamp(), visionStandardDev); } - // Log camera data + // Log camera datadata Logger.recordOutput("Vision/Camera" + Integer.toString(cameraIndex) + "/TagPoses", tagPoses.toArray(new Pose3d[tagPoses.size()])); Logger.recordOutput("Vision/Camera" + Integer.toString(cameraIndex) + "/RobotPoses", robotPoses.toArray(new Pose3d[robotPoses.size()])); Logger.recordOutput("Vision/Camera" + Integer.toString(cameraIndex) + "/RobotPosesAccepted", robotPosesAccepted.toArray(new Pose3d[robotPosesAccepted.size()])); @@ -173,6 +170,25 @@ private void processVision() { } private boolean shouldBeRejected(PoseObservation observation) { + boolean observedLadder = false; + boolean observedOutpost = false; + + for (Short tagObserved : observation.tagsObserved()) { + if (APRIL_TAG_IGNORE.contains(tagObserved)) { + observedLadder = true; + break; + } + if (observedLadder) break; + } + + for (Short tagObserved : observation.tagsObserved()) { + if (HUMAN_TAGS.contains(tagObserved)) { + observedOutpost = true; + break; + } + if (observedOutpost) break; + } + return ( observation.tagCount() == 0 || // Must have at least one tag (observation.tagCount() == 1 && observation.ambiguity() > maxAmbiguity) || // Cannot be high ambiguity @@ -192,8 +208,11 @@ public Matrix calculateStandardDev(PoseObservation observation) { double degStds; if (observation.tagCount() == 1) { double poseDifference = observation.pose().getTranslation().toTranslation2d().getDistance(Drive.getInstance().getPose().getTranslation()); + if (seenReefTags(observation) && observation.avgTagArea() > 0.2) { + xyStds = 0.5; + } // 1 target with large area and close to estimated pose - if (observation.avgTagArea() > 0.8 && poseDifference < 0.5) { + else if (observation.avgTagArea() > 0.8 && poseDifference < 0.5) { xyStds = 0.5; } // 1 target farther away and estimated pose is close @@ -209,4 +228,8 @@ else if (observation.avgTagArea() > 0.1 && poseDifference < 0.3) { return VecBuilder.fill(xyStds, xyStds, degStds); } } + + private boolean seenReefTags(PoseObservation observation) { + return allianceHubTags.contains(observation.tagsObserved().toArray()[0]); + } } diff --git a/src/main/java/frc/robot/Subsystems/Vision/VisionConstants.java b/src/main/java/frc/robot/Subsystems/Vision/VisionConstants.java index 2c88972..9315a94 100644 --- a/src/main/java/frc/robot/Subsystems/Vision/VisionConstants.java +++ b/src/main/java/frc/robot/Subsystems/Vision/VisionConstants.java @@ -15,6 +15,7 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.AngularVelocity; import frc.robot.Subsystems.Drive.Drive; +import java.util.Set; public class VisionConstants { @@ -27,29 +28,33 @@ public enum CameraResolution { // This is comp dependent public static final boolean USE_WELDED_FIELD = true; - public static final AprilTagFieldLayout APRIL_TAG_FIELD_LAYOUT = AprilTagFieldLayout.loadField(USE_WELDED_FIELD ? AprilTagFields.k2025ReefscapeWelded : AprilTagFields.k2025ReefscapeAndyMark); + public static final AprilTagFieldLayout APRIL_TAG_FIELD_LAYOUT = AprilTagFieldLayout.loadField(USE_WELDED_FIELD ? AprilTagFields.k2026RebuiltWelded : AprilTagFields.k2026RebuiltAndymark); public record VisionMeasurment(Pose2d pose, double timestamp, Matrix standardDev) {} - public static final String CAM_1_NAME = "Camera 1"; - public static final Translation3d ROBOT_TO_CAM1_TRANSLATION = new Translation3d(Units.inchesToMeters(11.809459), Units.inchesToMeters(11.164206), Units.inchesToMeters(8.887162)); - public static final Rotation3d ROBOT_TO_CAM1_ROTATION = new Rotation3d(0, Math.toRadians(-10), Math.toRadians(-30.4)); - public static final Transform3d ROBOT_TO_CAM1 = new Transform3d(ROBOT_TO_CAM1_TRANSLATION, ROBOT_TO_CAM1_ROTATION); + // Front Left + public static final String FRONT_CAM_1_NAME = "Front Left Camera"; + public static final Translation3d ROBOT_TO_FRONT_CAM_1_TRANSLATION = new Translation3d(Units.inchesToMeters(0), Units.inchesToMeters(11.164206), Units.inchesToMeters(8.887162)); + public static final Rotation3d ROBOT_TO_FRONT_CAM_1_ROTATION = new Rotation3d(0, Math.toRadians(-10), Math.toRadians(-30.4)); + public static final Transform3d ROBOT_TO_FRONT_CAM_1 = new Transform3d(ROBOT_TO_FRONT_CAM_1_TRANSLATION, ROBOT_TO_FRONT_CAM_1_ROTATION); - public static final String CAM_2_NAME = "Camera 2"; - public static final Translation3d ROBOT_TO_CAM2_TRANSLATION = new Translation3d(Units.inchesToMeters(11.809459), Units.inchesToMeters(-11.164206), Units.inchesToMeters(8.887162)); - public static final Rotation3d ROBOT_TO_CAM2_ROTATION = new Rotation3d(0, Math.toRadians(-10), Math.toRadians(27.8)); - public static final Transform3d ROBOT_TO_CAM2 = new Transform3d(ROBOT_TO_CAM2_TRANSLATION, ROBOT_TO_CAM2_ROTATION); + // Front Right + public static final String FRONT_CAM_2_NAME = "Front Right Camera"; + public static final Translation3d ROBOT_TO_FRONT_CAM_2_TRANSLATION = new Translation3d(Units.inchesToMeters(5), Units.inchesToMeters(-11.164206), Units.inchesToMeters(8.887162)); + public static final Rotation3d ROBOT_TO_FRONT_CAM_2_ROTATION = new Rotation3d(0, Math.toRadians(-10), Math.toRadians(27.8)); + public static final Transform3d ROBOT_TO_FRONT_CAM_2 = new Transform3d(ROBOT_TO_FRONT_CAM_2_TRANSLATION, ROBOT_TO_FRONT_CAM_2_ROTATION); - public static final VisionIO[] SIM_IOS = new VisionIO[] { new VisionIOPhotonVisionSim(CAM_1_NAME, ROBOT_TO_CAM1, Drive.getInstance()::getPose), new VisionIOPhotonVisionSim(CAM_2_NAME, ROBOT_TO_CAM2, Drive.getInstance()::getPose) }; - public static final VisionIO[] REAL_IOS = new VisionIO[] { new VisionIOPhotonVision(CAM_1_NAME, ROBOT_TO_CAM1), new VisionIOPhotonVision(CAM_2_NAME, ROBOT_TO_CAM2) }; + public static final VisionIO[] FRONT_SIM_IOS = new VisionIO[] { new VisionIOPhotonVisionSim(FRONT_CAM_1_NAME, ROBOT_TO_FRONT_CAM_1, Drive.getInstance()::getPose), new VisionIOPhotonVisionSim(FRONT_CAM_2_NAME, ROBOT_TO_FRONT_CAM_2, Drive.getInstance()::getPose) }; + + public static final VisionIO[] FRONT_REAL_IOS = new VisionIO[] { new VisionIOPhotonVision(FRONT_CAM_1_NAME, ROBOT_TO_FRONT_CAM_1), new VisionIOPhotonVision(FRONT_CAM_2_NAME, ROBOT_TO_FRONT_CAM_2) }; public static final double CAMERA_DEBOUNCE_TIME = 0.5; // TODO: What camera resolutions actually are these? Assuming they're high bc // 1080p is high // we never even use these why are they here - public static final CameraResolution RESOLUTION = CameraResolution.HIGH_RESOLUTION; + public static final CameraResolution BACK_RESOLUTION = CameraResolution.HIGH_RESOLUTION; + public static final CameraResolution FRONT_RESOLUTION = CameraResolution.HIGH_RESOLUTION; public static final int CAMERA_WIDTH = 1200; public static final int CAMERA_HEIGHT = 800; @@ -60,6 +65,13 @@ public record VisionMeasurment(Pose2d pose, double timestamp, Matrix sta public static final int AVG_LATENCY_MS = 40; public static final int LATENCY_STD_DEV_MS = 10; + //April Tag Lists + public static final Set HUMAN_TAGS = Set.of((short) 14, (short) 13, (short) 29, (short) 30); + public static final Set RED_HUB_TAGS = Set.of((short) 8, (short) 5, (short) 4, (short) 3, (short) 9, (short) 10, (short) 11, (short) 2); + public static final Set BLUE_HUB_TAGS = Set.of((short) 18, (short) 27, (short) 26, (short) 25, (short) 21, (short) 24, (short) 19, (short) 20); + public static final Set TRENCH_TAGS = Set.of((short) 7, (short) 6, (short) 12, (short) 1, (short) 17, (short) 28, (short) 22, (short) 23); + public static final Set APRIL_TAG_IGNORE = Set.of((short) 16, (short) 15, (short) 31, (short) 32); + // AKIT TEMPLATE STUFF // Basic filtering thresholds diff --git a/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVision.java index 9361e3c..5e9abc3 100644 --- a/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVision.java +++ b/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVision.java @@ -21,7 +21,7 @@ public class VisionIOPhotonVision implements VisionIO { * Creates a new VisionIOPhotonVision. * * @param name The configured name of the camera. - * @param robotToCamera The 3D position of the camera relative to the robot. + * @param rotationSupplier The 3D position of the camera relative to the robot. */ public VisionIOPhotonVision(String name, Transform3d robotToCamera) { camera = new PhotonCamera(name); @@ -47,6 +47,9 @@ public void logOutputs(VisionIOOutputs outputs) { if (result.multitagResult.isPresent()) { // Multitag result var multitagResult = result.multitagResult.get(); + // Skips whenever a camera only sees barge tags + if (multitagResult.fiducialIDsUsed.size() == 1 && APRIL_TAG_IGNORE.contains(multitagResult.fiducialIDsUsed.get(0))) continue; + // Calculate robot pose Transform3d fieldToCamera = multitagResult.estimatedPose.best; Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); @@ -116,7 +119,7 @@ public void logOutputs(VisionIOOutputs outputs) { // Save tag IDs to inputs objects outputs.tagIds = new int[tagIds.size()]; - int i = 0; // RAGE BAIT CODE + int i = 0; for (int id : tagIds) { outputs.tagIds[i++] = id; } diff --git a/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVisionSim.java b/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVisionSim.java index 278a325..3502b22 100644 --- a/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVisionSim.java +++ b/src/main/java/frc/robot/Subsystems/Vision/VisionIOPhotonVisionSim.java @@ -26,11 +26,11 @@ public VisionIOPhotonVisionSim(String name, Transform3d robotToCamera, Supplier< } // Add sim camera - // TODO: Uh like idrc about this ngl, but we can have a sim thats 4 deg more accurate if we want var cameraProperties = new SimCameraProperties(); - // cameraProperties.setAvgLatencyMs(AVG_LATENCY_MS); - // cameraProperties.setLatencyStdDevMs(LATENCY_STD_DEV_MS); - // cameraProperties.setCalibError(CALIB_ERROR_AVG, CALIB_ERROR_STD_DEV); + // get rid of if weird suff happens + cameraProperties.setAvgLatencyMs(AVG_LATENCY_MS); + cameraProperties.setLatencyStdDevMs(LATENCY_STD_DEV_MS); + cameraProperties.setCalibError(CALIB_ERROR_AVG, CALIB_ERROR_STD_DEV); cameraProperties.setFPS(CAMERA_FPS); cameraSim = new PhotonCameraSim(camera, cameraProperties); visionSim.addCamera(cameraSim, robotToCamera); diff --git a/src/main/java/frc/robot/subsystems/Intake/Intake.java b/src/main/java/frc/robot/subsystems/Intake/Intake.java index c4c4567..d56bae9 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake/Intake.java @@ -13,7 +13,7 @@ public class Intake extends Subsystem { private static Intake instance; private final IntakeIO io; - private final IntakeIO.IntakeIOInputs inputs = new IntakeIO.IntakeIOInputs(); + private final IntakeIO.IntakeIOOutputs outputs = new IntakeIO.IntakeIOOutputs(); private final SimpleMotorFeedforward spinFF = new SimpleMotorFeedforward(SPIN_kS, SPIN_kV, SPIN_kA); private Intake() { @@ -34,21 +34,18 @@ public static Intake getInstance() { @Override protected void runState() { - //asking for units explicitly - double linearPos = getState().linearPos.in(Meters); - double spinSpeed = getState().spinSpeed.in(RotationsPerSecond); - - io.setLinearPosition(linearPos); - io.setSpinVelocity(spinSpeed, spinFF.calculate(spinSpeed)); - io.updateInputs(inputs); - - Logger.recordOutput(SUBSYSTEM_NAME + "/SpinVelocityRPS", inputs.spinVelocityRPS); - Logger.recordOutput(SUBSYSTEM_NAME + "/SpinAppliedVolts", inputs.spinAppliedVolts); - Logger.recordOutput(SUBSYSTEM_NAME + "/SpinCurrentAmps", inputs.spinCurrentAmps); - Logger.recordOutput(SUBSYSTEM_NAME + "/LinearPositionMeters", inputs.linearPositionMeters); - Logger.recordOutput(SUBSYSTEM_NAME + "/LinearVelocityMetersPerSec", inputs.linearVelocityMetersPerSec); - Logger.recordOutput(SUBSYSTEM_NAME + "/LinearAppliedVolts", inputs.linearAppliedVolts); - Logger.recordOutput(SUBSYSTEM_NAME + "/LinearCurrentAmps", inputs.linearCurrentAmps); + io.setLinearPosition(getState().getLinearPos()); + io.setSpinVelocity(getState().getSpinSpeed(), spinFF.calculate(getState().getSpinSpeed().in(RotationsPerSecond))); + io.logOutputs(outputs); + Logger.recordOutput(SUBSYSTEM_NAME + "/SpinVelocityRPS", outputs.spinVelocity.in(RotationsPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/SpinSetpointRPS", outputs.spinSetpoint.in(RotationsPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/SpinAppliedVolts", outputs.spinAppliedVolts); + Logger.recordOutput(SUBSYSTEM_NAME + "/SpinCurrentAmps", outputs.spinCurrentAmps); + Logger.recordOutput(SUBSYSTEM_NAME + "/LinearPositionMeters", outputs.linearPosition.in(Meters)); + Logger.recordOutput(SUBSYSTEM_NAME + "/LinearSetpointMeters", outputs.linearSetpoint.in(Meters)); + Logger.recordOutput(SUBSYSTEM_NAME + "/LinearVelocityMetersPerSec", outputs.linearVelocity.in(MetersPerSecond)); + Logger.recordOutput(SUBSYSTEM_NAME + "/LinearAppliedVolts", outputs.linearAppliedVolts); + Logger.recordOutput(SUBSYSTEM_NAME + "/LinearCurrentAmps", outputs.linearCurrentAmps); } public TalonFX getSpinMotor() { diff --git a/src/main/java/frc/robot/subsystems/Intake/IntakeConstants.java b/src/main/java/frc/robot/subsystems/Intake/IntakeConstants.java index 64501f0..63302b5 100644 --- a/src/main/java/frc/robot/subsystems/Intake/IntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/Intake/IntakeConstants.java @@ -1,6 +1,7 @@ package frc.robot.Subsystems.Intake; import com.ctre.phoenix6.configs.Slot0Configs; //need to add via phoenix tuner +import org.team7525.controlConstants.PIDConstants; public class IntakeConstants { @@ -8,7 +9,7 @@ public class IntakeConstants { public static final double GEARING = 1; public static final double LINEAR_GEARING = 10.0; // figure out on CAD - public static final double LINEAR_METERS_PER_ROTATION = 0.005; // Check CAD/ motor specs + public static final double LINEAR_METERS_PER_ROTATION = 0.1; // Check CAD/ motor specs // States public static final double INTAKE_IN_POS = 0.0; @@ -16,25 +17,23 @@ public class IntakeConstants { public static final double SPIN_SPEED_INTAKE = 60.0; // RPS - public static final double SPIN_kS = 0.1; //tune - public static final double SPIN_kV = 0.12; // 12v I think? - public static final double SPIN_kA = 0.0; //tune + public static final double SPIN_kS = 0.0003; // Sim tuned + public static final double SPIN_kV = 0.00934498; // Sim tuned + public static final double SPIN_kA = 0.0; // Not needed for thuis prob public static final Slot0Configs LINEAR_SLOT_0_CONFIGS = new Slot0Configs().withKP(0.5).withKI(0).withKD(0); public static final Slot0Configs SPIN_SLOT_0_CONFIGS = new Slot0Configs().withKP(0.1).withKI(0).withKD(0).withKV(SPIN_kV); public static class Real { - public static final int SPIN_MOTOR_ID = 20; //make real - public static final int LINEAR_ACTUATOR_ID = 21; + public static final int SPIN_MOTOR_ID = 35; //make real + public static final int LINEAR_ACTUATOR_ID = 36; } - public record PIDConstants(double kP, double kI, double kD) {} - public static class Sim { public static final int NUM_MOTORS = 1; - public static final double MOTOR_MOI = 0.00001; - public static final PIDConstants LINEAR_PID = new PIDConstants(10.0, 0.0, 0.0); // Tune in sim + public static final double MOTOR_MOI = 0.0001; + public static final PIDConstants LINEAR_PID = new PIDConstants(5.5, 0.0, 0.008); // Tuned in sim } } } diff --git a/src/main/java/frc/robot/subsystems/Intake/IntakeIO.java b/src/main/java/frc/robot/subsystems/Intake/IntakeIO.java index 55218c3..11fe63a 100644 --- a/src/main/java/frc/robot/subsystems/Intake/IntakeIO.java +++ b/src/main/java/frc/robot/subsystems/Intake/IntakeIO.java @@ -1,25 +1,38 @@ package frc.robot.Subsystems.Intake; +import static edu.wpi.first.units.Units.Amps; +import static edu.wpi.first.units.Units.Meters; +import static edu.wpi.first.units.Units.MetersPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.Volts; + import com.ctre.phoenix6.hardware.TalonFX; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Distance; +import edu.wpi.first.units.measure.LinearVelocity; +import edu.wpi.first.units.measure.Voltage; public interface IntakeIO { - public static class IntakeIOInputs { - - public double spinVelocityRPS; - public double spinAppliedVolts; - public double spinCurrentAmps; - - public double linearPositionMeters; - public double linearVelocityMetersPerSec; - public double linearAppliedVolts; - public double linearCurrentAmps; + public static class IntakeIOOutputs { + + public AngularVelocity spinVelocity = RotationsPerSecond.of(0); + public AngularVelocity spinSetpoint = RotationsPerSecond.of(0); + public Voltage spinAppliedVolts = Volts.of(0); + public Current spinCurrentAmps = Amps.of(0); + + public Distance linearPosition = Meters.of(0); + public Distance linearSetpoint = Meters.of(0); + public LinearVelocity linearVelocity = MetersPerSecond.of(0); + public Voltage linearAppliedVolts = Volts.of(0); + public Current linearCurrentAmps = Amps.of(0); } - public void updateInputs(IntakeIOInputs inputs); + public void logOutputs(IntakeIOOutputs outputs); - public void setSpinVelocity(double rps, double feedforward); + public void setSpinVelocity(AngularVelocity speed, double feedforward); - public void setLinearPosition(double meters); + public void setLinearPosition(Distance setpoint); public TalonFX getSpinMotor(); } diff --git a/src/main/java/frc/robot/subsystems/Intake/IntakeIOSim.java b/src/main/java/frc/robot/subsystems/Intake/IntakeIOSim.java index f67d56e..1166d18 100644 --- a/src/main/java/frc/robot/subsystems/Intake/IntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/Intake/IntakeIOSim.java @@ -8,57 +8,70 @@ import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import frc.robot.GlobalConstants; import frc.robot.Subsystems.Intake.IntakeConstants.Sim; -public class IntakeIOSim implements IntakeIO { +public class IntakeIOSim extends IntakeIOTalonFX { private DCMotorSim spinSim; private TalonFXSimState spinSimState; - private TalonFX spinMotor; - + private AngularVelocity speed; + private Distance setpoint; private DCMotorSim linearSim; private TalonFXSimState linearSimState; - private TalonFX linearMotor; private final PIDController linearController; public IntakeIOSim() { + speed = RotationsPerSecond.of(0); + setpoint = Meters.of(0); spinSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, 1), DCMotor.getFalcon500(1)); - spinMotor = new TalonFX(Real.SPIN_MOTOR_ID); spinSimState = new TalonFXSimState(spinMotor); linearSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, LINEAR_GEARING), DCMotor.getFalcon500(1)); - linearMotor = new TalonFX(Real.LINEAR_ACTUATOR_ID); linearSimState = new TalonFXSimState(linearMotor); - linearController = new PIDController(Sim.LINEAR_PID.kP(), Sim.LINEAR_PID.kI(), Sim.LINEAR_PID.kD()); + linearController = new PIDController(Sim.LINEAR_PID.kP, Sim.LINEAR_PID.kI, Sim.LINEAR_PID.kD); } @Override - public void updateInputs(IntakeIOInputs inputs) { + public void logOutputs(IntakeIOOutputs outputs) { spinSim.update(GlobalConstants.SIMULATION_PERIOD); spinSimState.setRotorVelocity(spinSim.getAngularVelocityRPM() / 60); spinSimState.setRawRotorPosition(spinSim.getAngularPositionRotations()); spinSimState.setSupplyVoltage(12.0); + //SmartDashboard.putData("Intake TUNER", linearController); + linearSim.update(GlobalConstants.SIMULATION_PERIOD); linearSimState.setRotorVelocity((linearSim.getAngularVelocityRPM() / 60) * LINEAR_GEARING); linearSimState.setRawRotorPosition(linearSim.getAngularPositionRotations() * LINEAR_GEARING); linearSimState.setSupplyVoltage(12.0); - inputs.spinVelocityRPS = spinMotor.getVelocity().getValue().in(RotationsPerSecond); - inputs.linearPositionMeters = linearSim.getAngularPositionRotations() * LINEAR_METERS_PER_ROTATION; + outputs.spinVelocity = spinMotor.getVelocity().getValue(); + outputs.spinSetpoint = speed; + outputs.spinAppliedVolts = spinMotor.getMotorVoltage().getValue(); + outputs.spinCurrentAmps = spinMotor.getStatorCurrent().getValue(); + + outputs.linearAppliedVolts = linearMotor.getMotorVoltage().getValue(); + outputs.linearCurrentAmps = linearMotor.getStatorCurrent().getValue(); + outputs.linearPosition = Meters.of(linearSim.getAngularPositionRotations() * LINEAR_METERS_PER_ROTATION); + outputs.linearSetpoint = setpoint; + outputs.linearVelocity = MetersPerSecond.of(linearSim.getAngularVelocity().in(RotationsPerSecond) * LINEAR_METERS_PER_ROTATION); } @Override - public void setSpinVelocity(double rps, double feedforward) { - spinSim.setInputVoltage(feedforward); + public void setSpinVelocity(AngularVelocity speed, double feedforward) { + this.speed = speed; + spinSim.setInputVoltage(12 * feedforward); } @Override - public void setLinearPosition(double meters) { - linearSim.setInputVoltage(linearController.calculate(linearSim.getAngularPositionRotations(), meters / LINEAR_METERS_PER_ROTATION)); - } //pid only for sim, irl uses talon pid + public void setLinearPosition(Distance setpoint) { + this.setpoint = setpoint; + linearSim.setInputVoltage(12 * linearController.calculate(linearSim.getAngularPositionRotations(), setpoint.in(Meters) / LINEAR_METERS_PER_ROTATION)); + } // pid only for sim, irl uses talon pid @Override public TalonFX getSpinMotor() { diff --git a/src/main/java/frc/robot/subsystems/Intake/IntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/Intake/IntakeIOTalonFX.java index 9f60596..779fe24 100644 --- a/src/main/java/frc/robot/subsystems/Intake/IntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/Intake/IntakeIOTalonFX.java @@ -1,7 +1,6 @@ package frc.robot.Subsystems.Intake; import static edu.wpi.first.units.Units.*; -import static frc.robot.GlobalConstants.*; import static frc.robot.Subsystems.Intake.IntakeConstants.*; import com.ctre.phoenix6.configs.TalonFXConfiguration; @@ -9,12 +8,14 @@ import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; import frc.robot.Subsystems.Intake.IntakeConstants.Real; public class IntakeIOTalonFX implements IntakeIO { - private final TalonFX spinMotor; - private final TalonFX linearMotor; // idk what to call it but the linear actuator? + protected final TalonFX spinMotor; + protected final TalonFX linearMotor; // idk what to call it but the linear actuator? private final PositionVoltage linearRequest = new PositionVoltage(0); //talon pid cool private final VelocityVoltage spinRequest = new VelocityVoltage(0); @@ -38,25 +39,25 @@ public IntakeIOTalonFX() { } @Override - public void updateInputs(IntakeIOInputs inputs) { - inputs.spinVelocityRPS = spinMotor.getVelocity().getValue().in(RotationsPerSecond); - inputs.spinAppliedVolts = spinMotor.getMotorVoltage().getValueAsDouble(); - inputs.spinCurrentAmps = spinMotor.getStatorCurrent().getValueAsDouble(); + public void logOutputs(IntakeIOOutputs outputs) { + outputs.spinVelocity = spinMotor.getVelocity().getValue(); + outputs.spinAppliedVolts = spinMotor.getMotorVoltage().getValue(); + outputs.spinCurrentAmps = spinMotor.getStatorCurrent().getValue(); - inputs.linearPositionMeters = linearMotor.getPosition().getValueAsDouble() * LINEAR_METERS_PER_ROTATION; - inputs.linearVelocityMetersPerSec = linearMotor.getVelocity().getValueAsDouble() * LINEAR_METERS_PER_ROTATION; - inputs.linearAppliedVolts = linearMotor.getMotorVoltage().getValueAsDouble(); - inputs.linearCurrentAmps = linearMotor.getStatorCurrent().getValueAsDouble(); + outputs.linearPosition = Meters.of(linearMotor.getPosition().getValueAsDouble() * LINEAR_METERS_PER_ROTATION); + outputs.linearVelocity = MetersPerSecond.of(linearMotor.getVelocity().getValueAsDouble() * LINEAR_METERS_PER_ROTATION); + outputs.linearAppliedVolts = linearMotor.getMotorVoltage().getValue(); + outputs.linearCurrentAmps = linearMotor.getStatorCurrent().getValue(); } @Override - public void setSpinVelocity(double rps, double feedforward) { - spinMotor.setControl(spinRequest.withVelocity(rps).withFeedForward(feedforward)); + public void setSpinVelocity(AngularVelocity speed, double feedforward) { + spinMotor.setControl(spinRequest.withVelocity(speed.in(RotationsPerSecond)).withFeedForward(feedforward)); } @Override - public void setLinearPosition(double meters) { - linearMotor.setControl(linearRequest.withPosition(meters / LINEAR_METERS_PER_ROTATION)); + public void setLinearPosition(Distance setpoint) { + linearMotor.setControl(linearRequest.withPosition(setpoint.in(Meters) / LINEAR_METERS_PER_ROTATION)); } @Override diff --git a/src/main/java/frc/robot/subsystems/Intake/IntakeStates.java b/src/main/java/frc/robot/subsystems/Intake/IntakeStates.java index ca3e2f7..bda0f2a 100644 --- a/src/main/java/frc/robot/subsystems/Intake/IntakeStates.java +++ b/src/main/java/frc/robot/subsystems/Intake/IntakeStates.java @@ -26,4 +26,12 @@ public enum IntakeStates implements SubsystemStates { public String getStateString() { return stateString; } + + public Distance getLinearPos() { + return linearPos; + } + + public AngularVelocity getSpinSpeed() { + return spinSpeed; + } } diff --git a/vendordeps/Phoenix6-26.1.0.json b/vendordeps/Phoenix6-26.1.1.json similarity index 92% rename from vendordeps/Phoenix6-26.1.0.json rename to vendordeps/Phoenix6-26.1.1.json index dc5dc62..7a0eca0 100644 --- a/vendordeps/Phoenix6-26.1.0.json +++ b/vendordeps/Phoenix6-26.1.1.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix6-26.1.0.json", + "fileName": "Phoenix6-26.1.1.json", "name": "CTRE-Phoenix (v6)", - "version": "26.1.0", + "version": "26.1.1", "frcYear": "2026", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "26.1.0" + "version": "26.1.1" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +152,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -194,7 +194,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -208,7 +208,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "26.1.0", + "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -224,7 +224,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -240,7 +240,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -256,7 +256,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -272,7 +272,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -288,7 +288,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -304,7 +304,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -320,7 +320,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -336,7 +336,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -352,7 +352,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFXS", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProTalonFXS", "headerClassifier": "headers", "sharedLibrary": true, @@ -368,7 +368,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -384,7 +384,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -400,7 +400,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -416,7 +416,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdi", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProCANdi", "headerClassifier": "headers", "sharedLibrary": true, @@ -432,7 +432,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANdle", - "version": "26.1.0", + "version": "26.1.1", "libName": "CTRE_SimProCANdle", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Phoenix6-replay-26.1.0.json b/vendordeps/Phoenix6-replay-26.1.0.json deleted file mode 100644 index 81d61c9..0000000 --- a/vendordeps/Phoenix6-replay-26.1.0.json +++ /dev/null @@ -1,491 +0,0 @@ -{ - "fileName": "Phoenix6-replay-26.1.0.json", - "name": "CTRE-Phoenix (v6) Replay (DISABLED)", - "version": "26.1.0", - "frcYear": "2026", - "uuid": "00000000-0000-0000-0000-000000000000", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-replay-frc2026-latest.json", - - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "26.1.0" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "api-cpp-replay", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "tools-replay", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdle", - "version": "26.1.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "26.1.0", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "26.1.0", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "wpiapi-cpp-replay", - "version": "26.1.0", - "libName": "CTRE_Phoenix6_WPIReplay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "tools-replay", - "version": "26.1.0", - "libName": "CTRE_PhoenixTools_Replay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "26.1.0", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "26.1.0", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "26.1.0", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "26.1.0", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "26.1.0", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "26.1.0", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "26.1.0", - "libName": "CTRE_SimProTalonFXS", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "26.1.0", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "26.1.0", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "26.1.0", - "libName": "CTRE_SimProCANrange", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "26.1.0", - "libName": "CTRE_SimProCANdi", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdle", - "version": "26.1.0", - "libName": "CTRE_SimProCANdle", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} \ No newline at end of file diff --git a/vendordeps/ThriftyLib-2026.0.0.json b/vendordeps/ThriftyLib-2026.json similarity index 81% rename from vendordeps/ThriftyLib-2026.0.0.json rename to vendordeps/ThriftyLib-2026.json index f09218a..9aa5808 100644 --- a/vendordeps/ThriftyLib-2026.0.0.json +++ b/vendordeps/ThriftyLib-2026.json @@ -1,7 +1,7 @@ { - "fileName": "ThriftyLib-2026.0.0.json", + "fileName": "ThriftyLib-2026.json", "name": "ThriftyLib", - "version": "2026.0.0", + "version": "2026.0.1", "frcYear": "2026", "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.thethriftybot.frc", "artifactId": "ThriftyLib-java", - "version": "2026.0.0" + "version": "2026.0.1" } ], "jniDependencies": [], diff --git a/vendordeps/maple-sim-0.4.0-beta.json b/vendordeps/maple-sim-0.4.0-beta.json new file mode 100644 index 0000000..d9bf4ab --- /dev/null +++ b/vendordeps/maple-sim-0.4.0-beta.json @@ -0,0 +1,26 @@ +{ + "fileName": "maple-sim-0.4.0-beta.json", + "name": "maplesim", + "version": "0.4.0-beta", + "frcYear": "2026", + "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", + "mavenUrls": [ + "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases", + "https://repo1.maven.org/maven2" + ], + "jsonUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json", + "javaDependencies": [ + { + "groupId": "org.ironmaple", + "artifactId": "maplesim-java", + "version": "0.4.0-beta" + }, + { + "groupId": "org.dyn4j", + "artifactId": "dyn4j", + "version": "5.0.2" + } + ], + "jniDependencies": [], + "cppDependencies": [] +} \ No newline at end of file