diff --git a/ascope_assets/Robot_Alpha/config.json b/ascope_assets/Robot_Alpha/config.json index 3736882..ac8b976 100644 --- a/ascope_assets/Robot_Alpha/config.json +++ b/ascope_assets/Robot_Alpha/config.json @@ -26,9 +26,9 @@ 1304 ], "position": [ - 0.287, - 0.260, - 0.211 + 0.289591, + 0.261649, + 0.205829 ], "rotations": [ { @@ -45,9 +45,9 @@ 1304 ], "position": [ - 0.287, - -0.260, - 0.211 + 0.289591, + -0.261649, + 0.205829 ], "rotations": [ { @@ -114,4 +114,4 @@ ] } ] -} +} \ No newline at end of file diff --git a/build.gradle b/build.gradle index c282c24..2781270 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.2.1" + id "edu.wpi.first.GradleRIO" version "2025.3.1" id "com.peterabeles.gversion" version "1.10" id "com.diffplug.spotless" version "6.12.0" id "io.freefair.lombok" version "8.6" diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index cc41c8e..3c0df25 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -21,6 +21,8 @@ public class FieldConstants { public static final double fieldLength = Units.inchesToMeters(690.876); public static final double fieldWidth = Units.inchesToMeters(317); + public static final Translation2d fieldCenter = + new Translation2d(fieldLength / 2, fieldWidth / 2); public static final double startingLineX = Units.inchesToMeters(299.438); // Measured from the inside of starting // line @@ -57,14 +59,14 @@ public static class CoralStation { } public static class Reef { - public static final Translation2d center = + public static final Translation2d centerOfReef = new Translation2d(Units.inchesToMeters(176.746), Units.inchesToMeters(158.501)); public static final double faceToZoneLine = Units.inchesToMeters(12); // Side of the reef to the inside of the // reef zone line public static final Pose2d[] centerFaces = - new Pose2d[6]; // Starting facing the driver station in clockwise + new Pose2d[12]; // Starting facing the driver station in clockwise // order public static final List> branchPositions = new ArrayList<>(); // Starting at the right @@ -105,15 +107,31 @@ public static class Reef { Units.inchesToMeters(130.144), Rotation2d.fromDegrees(-120)); + centerFaces[6] = centerFaces[0].rotateAround(fieldCenter, Rotation2d.k180deg); + centerFaces[7] = centerFaces[1].rotateAround(fieldCenter, Rotation2d.k180deg); + centerFaces[8] = centerFaces[2].rotateAround(fieldCenter, Rotation2d.k180deg); + centerFaces[9] = centerFaces[3].rotateAround(fieldCenter, Rotation2d.k180deg); + centerFaces[10] = centerFaces[4].rotateAround(fieldCenter, Rotation2d.k180deg); + centerFaces[11] = centerFaces[5].rotateAround(fieldCenter, Rotation2d.k180deg); + // Initialize branch positions - for (int face = 0; face < 6; face++) { + for (int face = 0; face < centerFaces.length; face++) { Map fillRight = new HashMap<>(); Map fillLeft = new HashMap<>(); for (var level : ReefHeight.values()) { - Pose2d poseDirection = - new Pose2d(center, Rotation2d.fromDegrees(180 - (60 * face))); - double adjustX = Units.inchesToMeters(30.738); - double adjustY = Units.inchesToMeters(6.469); + Pose2d poseDirection = new Pose2d(); + if (face < 6) { + poseDirection = + new Pose2d(centerOfReef, centerFaces[face].getRotation()); + } else { + poseDirection = + new Pose2d(centerOfReef.rotateAround(fieldCenter, Rotation2d.k180deg), + centerFaces[face].getRotation()); + } + + double adjustX = Units.inchesToMeters(30.738); // Depth of branch from reef face + double adjustY = Units.inchesToMeters(6.469); // Offset from reef face + // centerline to branch fillRight.put( level, @@ -153,6 +171,8 @@ public static class Reef { branchPositions.add(fillRight); branchPositions.add(fillLeft); } + + } } @@ -202,15 +222,20 @@ public static Pose2d getNearestReefBranch(Pose2d currentPose, ReefSide side) public static Pose2d getNearestCoralStation(Pose2d currentPose) { - double distanceToLeftStation = currentPose.getTranslation() - .getDistance(FieldConstants.CoralStation.leftCenterFace.getTranslation()); - double distanceToRightStation = currentPose.getTranslation() - .getDistance(FieldConstants.CoralStation.rightCenterFace.getTranslation()); - - if (distanceToLeftStation > distanceToRightStation) { - return FieldConstants.CoralStation.rightCenterFace; + if (currentPose.getTranslation().getX() > FieldConstants.fieldLength / 2) { + if (currentPose.getTranslation().getY() > FieldConstants.fieldWidth / 2) { + return FieldConstants.CoralStation.rightCenterFace + .rotateAround(FieldConstants.fieldCenter, Rotation2d.k180deg); + } else { + return FieldConstants.CoralStation.leftCenterFace + .rotateAround(FieldConstants.fieldCenter, Rotation2d.k180deg); + } } else { - return FieldConstants.CoralStation.leftCenterFace; + if (currentPose.getTranslation().getY() > FieldConstants.fieldWidth / 2) { + return FieldConstants.CoralStation.leftCenterFace; + } else { + return FieldConstants.CoralStation.rightCenterFace; + } } } } diff --git a/src/main/java/frc/robot/Ports.java b/src/main/java/frc/robot/Ports.java index e8d9ff0..8dda3e5 100644 --- a/src/main/java/frc/robot/Ports.java +++ b/src/main/java/frc/robot/Ports.java @@ -13,6 +13,7 @@ public class Ports { public static final CanDeviceId CLAW_LASERCAN = new CanDeviceId(16, "rio"); public static final CanDeviceId CLAW_ROLLER = new CanDeviceId(17, "rio"); + public static final CanDeviceId ARM_CANCODER = new CanDeviceId(18, "rio"); public static final CanDeviceId ARM_MAIN = new CanDeviceId(19, "rio"); @@ -23,6 +24,8 @@ public class Ports { public static final CanDeviceId ELEVATOR_MAIN = new CanDeviceId(22, "rio"); // Top Kraken public static final CanDeviceId ELEVATOR_FOLLOWER = new CanDeviceId(23, "rio"); // Bottom Kraken - public static final CanDeviceId CLIMBER = new CanDeviceId(24, "rio"); + public static final CanDeviceId CLIMBER = new CanDeviceId(24, "Drivetrain"); + + public static final CanDeviceId PDH = new CanDeviceId(25, "rio"); } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 9ab2420..b12eb3a 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -148,47 +148,11 @@ public void disabledInit() public void disabledPeriodic() { // Test + m_autonomousCommand = m_robotContainer.getAutonomousCommand(); var alliance = DriverStation.getAlliance(); - Pose2d test; // Test // Get currently selected command - m_autonomousCommand = m_robotContainer.getAutonomousCommand(); - // Check if is the same as the last one - if (m_autonomousCommand != m_lastAutonomousCommand && m_autonomousCommand != null) { - // Check if its contained in the list of our autos - if (AutoBuilder.getAllAutoNames().contains(m_autonomousCommand.getName())) { - // Clear the current path - m_pathsToShow.clear(); - // Grabs all paths from the auto - try { - for (PathPlannerPath path : PathPlannerAuto - .getPathGroupFromAutoFile(m_autonomousCommand.getName())) { - // Adds all poses to master list - m_pathsToShow.addAll(path.getPathPoses()); - } - } catch (IOException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } catch (ParseException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - // Displays all poses on Field2d widget depending on Alliance Side - if (alliance.isPresent() && alliance.get() == Alliance.Red) { - m_autoTraj.getObject("traj").setPoses(m_pathsToShow); - } else { - for (int i = 0; i < m_pathsToShow.size(); i++) { - test = m_pathsToShow.get(0).transformBy( - new Transform2d()); - Logger.recordOutput("m_pathsToShow" + i, m_pathsToShow.get(i)); - Logger.recordOutput("NEW_m_pathsToShow" + i, test); - } - } - // - m_autoTraj.setRobotPose(m_pathsToShow.get(0)); - } - } - m_lastAutonomousCommand = m_autonomousCommand; + } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 62c9d08..277ac16 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -39,6 +39,7 @@ import frc.robot.subsystems.Climber.ClimberIOSim; import frc.robot.subsystems.Climber.ClimberIOTalonFX; import frc.robot.subsystems.Elevator.*; +import frc.robot.subsystems.Elevator.Elevator.State; import frc.robot.subsystems.LED.LED; import frc.robot.subsystems.Vision.*; import frc.robot.subsystems.drive.*; @@ -75,45 +76,61 @@ public class RobotContainer { private final Superstructure m_superStruct; public final Vision m_vision; - public final LED m_LED; + // public final LED m_LED; // Trigger for algae/coral mode switching - private boolean coralModeEnabled = false; + private boolean coralModeEnabled = true; private Trigger isCoralMode = new Trigger(() -> coralModeEnabled); - // private final LaserCANSensor m_clawLaserCAN = - // new LaserCANSensor(Ports.CLAW_LASERCAN.getDeviceNumber(), Inches.of(6)); - // private final LaserCANSensor m_rampLaserCAN = - // new LaserCANSensor(Ports.RAMP_LASERCAN.getDeviceNumber(), Inches.of(6)); - /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { switch (Constants.currentMode) { case REAL: // Real robot, instantiate hardware IO implementations - m_drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFXReal(TunerConstants.FrontLeft), - new ModuleIOTalonFXReal(TunerConstants.FrontRight), - new ModuleIOTalonFXReal(TunerConstants.BackLeft), - new ModuleIOTalonFXReal(TunerConstants.BackRight), - (robotPose) -> { - }); + // m_drive = + // new Drive( + // new GyroIOPigeon2(), + // new ModuleIOTalonFXReal(TunerConstants.FrontLeft), + // new ModuleIOTalonFXReal(TunerConstants.FrontRight), + // new ModuleIOTalonFXReal(TunerConstants.BackLeft), + // new ModuleIOTalonFXReal(TunerConstants.BackRight), + // (robotPose) -> { + // }); m_profiledArm = new Arm(new ArmIOTalonFX(), false); m_profiledElevator = new Elevator(new ElevatorIOTalonFX(), false); - m_profiledClimber = new Climber(new ClimberIOTalonFX(), false); + // m_profiledClimber = new Climber(new ClimberIOTalonFX(), false); m_clawRoller = new ClawRoller(new ClawRollerIOTalonFX(), false); m_clawRollerLaserCAN = new ClawRollerLaserCAN(new ClawRollerLaserCANIOReal()); m_intakeLaserCAN = new IntakeLaserCAN(new IntakeLaserCANIOReal()); - m_vision = - new Vision( - m_drive, - new VisionIOPhotonVision(camera0Name, robotToCamera0), - new VisionIOPhotonVision(camera1Name, robotToCamera1)); + // m_vision = + // new Vision( + // m_drive, + // new VisionIOPhotonVision(camera0Name, robotToCamera0), + // new VisionIOPhotonVision(camera1Name, robotToCamera1)); + + // break; + + m_drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + (robotPose) -> { + }); + + // m_profiledArm = new Arm(new ArmIO() {}, true); + // m_profiledElevator = new Elevator(new ElevatorIO() {}, true); + m_profiledClimber = new Climber(new ClimberIO() {}, true); + // m_clawRoller = new ClawRoller(new ClawRollerIO() {}, true); + // m_clawRollerLaserCAN = new ClawRollerLaserCAN(new ClawRollerLaserCANIO() {}); + // m_intakeLaserCAN = new IntakeLaserCAN(new IntakeLaserCANIO() {}); + + m_vision = new Vision(m_drive, new VisionIO() {}, new VisionIO() {}); break; @@ -182,8 +199,8 @@ public RobotContainer() m_superStruct = new Superstructure(m_profiledArm, m_profiledElevator); // LED subsystem reads status from all other subsystems to control LEDs via CANdle - m_LED = new LED(m_driver, m_profiledArm, m_clawRoller, m_profiledClimber, m_drive, - m_profiledElevator, m_vision, m_clawRollerLaserCAN, isCoralMode); + // m_LED = new LED(m_driver, m_profiledArm, m_clawRoller, m_profiledClimber, m_drive, + // m_profiledElevator, m_vision, m_clawRollerLaserCAN, isCoralMode); // Logic Triggers registerNamedCommands(); @@ -208,8 +225,6 @@ public RobotContainer() "Drive SysId (Dynamic Forward)", m_drive.sysIdDynamic(SysIdRoutine.Direction.kForward)); m_autoChooser.addOption( "Drive SysId (Dynamic Reverse)", m_drive.sysIdDynamic(SysIdRoutine.Direction.kReverse)); - m_autoChooser.addOption("Elevator static", m_profiledElevator.staticCharacterization(2.0)); - m_autoChooser.addOption("Arm static", m_profiledArm.staticCharacterization(2.0)); // Configure the controller button and joystick bindings configureControllerBindings(); @@ -252,75 +267,77 @@ public Command setCoralAlgaeModeCommand() }); } - /** Use this method to define your joystick and button -> command mappings. */ + /** Button and Command mappings */ private void configureControllerBindings() { // Default command, normal field-relative drive m_drive.setDefaultCommand(joystickDrive()); - // Driver Back Button: Reset gyro / odometry - final Runnable setPose = - Constants.currentMode == Constants.Mode.SIM - ? () -> m_drive.setPose(m_driveSimulation.getSimulatedDriveTrainPose()) - : () -> m_drive - .setPose(new Pose2d(m_drive.getPose().getTranslation(), new Rotation2d())); - m_driver - .back() - .onTrue( - Commands.runOnce(setPose).ignoringDisable(true)); - // Driver Left Bumper: Face Nearest Reef Face - m_driver.leftBumper() - .whileTrue( - joystickDriveAtAngle( - () -> FieldConstants.getNearestReefFace(m_drive.getPose()).getRotation() - .rotateBy(Rotation2d.k180deg))); + // m_driver.leftBumper() + // .whileTrue( + // joystickDriveAtAngle( + // () -> FieldConstants.getNearestReefFace(m_drive.getPose()).getRotation() + // .rotateBy(Rotation2d.k180deg))); // Driver Left Bumper + Right Stick Right: Approach Nearest Right-Side Reef Branch - m_driver.leftBumper().and(m_driver.axisGreaterThan(XboxController.Axis.kRightX.value, 0.8)) - .whileTrue( - joystickApproach( - () -> FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT))); + // m_driver.leftBumper().and(m_driver.axisGreaterThan(XboxController.Axis.kRightX.value, + // 0.8)) + // .whileTrue( + // joystickApproach( + // () -> FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT))); // Driver Left Bumper + Right Stick Left: Approach Nearest Left-Side Reef Branch - m_driver.leftBumper().and(m_driver.axisLessThan(XboxController.Axis.kRightX.value, -0.8)) - .whileTrue( - joystickApproach( - () -> FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.LEFT))); + // m_driver.leftBumper().and(m_driver.axisLessThan(XboxController.Axis.kRightX.value, -0.8)) + // .whileTrue( + // joystickApproach( + // () -> FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.LEFT))); // Driver Left Bumper + Right Bumper: Approach Nearest Reef Face - m_driver.leftBumper().and(m_driver.rightBumper()) - .whileTrue( - joystickApproach(() -> FieldConstants.getNearestReefFace(m_drive.getPose()))); + // m_driver.leftBumper().and(m_driver.rightBumper()) + // .whileTrue( + // joystickApproach(() -> FieldConstants.getNearestReefFace(m_drive.getPose()))); // Driver A Button: Send Arm and Elevator to LEVEL_1 m_driver - .a().and(isCoralMode) + .a() .onTrue( m_superStruct.getTransitionCommand(Arm.State.LEVEL_1, Elevator.State.LEVEL_1)); // Driver A Button held and Right Bumper Pressed: Send Arm and Elevator to Processor m_driver - .a().and(isCoralMode.negate()) + .a().and(isCoralMode) .onTrue( m_superStruct.getTransitionCommand(Arm.State.ALGAE_GROUND, Elevator.State.ALGAE_SCORE)); // Driver X Button: Send Arm and Elevator to LEVEL_2 m_driver - .x() + .x().and(isCoralMode) .onTrue( m_superStruct.getTransitionCommand(Arm.State.LEVEL_2, Elevator.State.LEVEL_2)); + // Driver X Button: Send Arm and Elevator to LEVEL_2 + m_driver + .x().and(isCoralMode.negate()) + .onTrue( + m_superStruct.getTransitionCommand(Arm.State.ALGAE_LOW, Elevator.State.ALGAE_LOW)); + // Driver B Button: Send Arm and Elevator to LEVEL_3 m_driver - .b() + .b().and(isCoralMode) .onTrue( m_superStruct.getTransitionCommand(Arm.State.LEVEL_3, Elevator.State.LEVEL_3)); + m_driver + .b().and(isCoralMode.negate()) + .onTrue( + m_superStruct.getTransitionCommand(Arm.State.ALGAE_HIGH, + Elevator.State.ALGAE_HIGH)); + // Driver Y Button: Send Arm and Elevator to LEVEL_4 m_driver - .y().and(isCoralMode) + .y() .onTrue( m_superStruct.getTransitionCommand(Arm.State.LEVEL_4, Elevator.State.LEVEL_4)); @@ -329,104 +346,125 @@ private void configureControllerBindings() m_driver .y().and(isCoralMode.negate()) .onTrue( - m_superStruct.getTransitionCommand(Arm.State.LEVEL_4, Elevator.State.BARGE)); - // TODO: Test Arm Level 4 in Sim + m_superStruct.getTransitionCommand(Arm.State.BARGE, Elevator.State.BARGE)); + // Driver Right Trigger: Place Coral or Algae (Should be done once the robot is in position) m_driver.rightTrigger() - .whileTrue(m_clawRoller.setStateCommand(ClawRoller.State.EJECT)); + .whileTrue(m_clawRoller.setStateCommand(ClawRoller.State.SCORE)); + + // Driver Left Trigger: Drivetrain drive at coral station angle, prepare the elevator and // arm, Get Ready to Intake Coral m_driver - .leftTrigger().and(isCoralMode) + .leftTrigger() .whileTrue( - Commands.sequence( - joystickDriveAtAngle( - () -> FieldConstants.getNearestCoralStation(m_drive.getPose()) - .getRotation()), - m_profiledElevator.setStateCommand(Elevator.State.CORAL_INTAKE), - Commands.waitUntil(() -> m_profiledElevator.atPosition(0.1)) - .andThen(Commands.parallel( - m_profiledArm.setStateCommand(Arm.State.CORAL_INTAKE), - m_clawRoller.setStateCommand(ClawRoller.State.INTAKE)), - Commands.waitUntil(m_clawRollerLaserCAN.triggered) - .andThen(m_clawRoller.setStateCommand(ClawRoller.State.HOLDCORAL)))) + m_clawRoller.setStateCommandNoEnd(ClawRoller.State.INTAKE) .andThen( - Commands.parallel( - m_clawRoller.setStateCommand(ClawRoller.State.OFF), - m_profiledArm.setStateCommand(Arm.State.STOW)))); + m_superStruct + .getTransitionCommand(Arm.State.CORAL_INTAKE, + Elevator.State.CORAL_INTAKE)) + .andThen(Commands.waitUntil(m_intakeLaserCAN.triggered)) + .andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.INTAKESLOW)) + .andThen(Commands + .waitUntil(m_intakeLaserCAN.triggered.negate() + .and(m_clawRollerLaserCAN.triggered))) + .andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.SHUFFLE)) + .andThen(Commands + .waitUntil(m_intakeLaserCAN.triggered + .and(m_clawRollerLaserCAN.triggered))) + .andThen(m_clawRoller.setStateCommand(ClawRoller.State.HOLDCORAL))) + .onFalse(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.HOLDCORAL) + .andThen(m_superStruct + .getTransitionCommand(Arm.State.STOW, + Elevator.State.STOW))); + + // m_driver + // .leftTrigger().and(isCoralMode) + // .whileTrue( + // Commands.sequence( + // joystickDriveAtAngle( + // () -> FieldConstants.getNearestCoralStation(m_drive.getPose()) + // .getRotation()), + // m_profiledElevator.setStateCommand(Elevator.State.CORAL_INTAKE), + // Commands.waitUntil(() -> m_profiledElevator.atPosition(0.1)) + // .andThen(Commands.parallel( + // m_profiledArm.setStateCommand(Arm.State.CORAL_INTAKE), + // m_clawRoller.setStateCommand(ClawRoller.State.INTAKE)), + // Commands.waitUntil(m_clawRollerLaserCAN.triggered) + // .andThen(m_clawRoller.setStateCommand(ClawRoller.State.HOLDCORAL)))) + // .andThen( + // Commands.parallel( + // m_clawRoller.setStateCommand(ClawRoller.State.OFF), + // m_profiledArm.setStateCommand(Arm.State.STOW)))); + // Driver Left Trigger + Right Bumper: Algae Intake - m_driver.leftTrigger().and(isCoralMode.negate()).whileTrue( - Commands.sequence( - (FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT) - .getTranslation().getX() > 0) - ? m_profiledElevator.setStateCommand(Elevator.State.ALGAE_HIGH) - : m_profiledElevator.setStateCommand(Elevator.State.ALGAE_LOW), - m_clawRoller.setStateCommand(ClawRoller.State.INTAKE), - Commands.waitUntil(m_clawRoller.stalled) - .andThen(m_clawRoller.setStateCommand(ClawRoller.State.OFF))) - .andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW))); - m_driver.rightTrigger().whileTrue(m_clawRoller.setStateCommand(ClawRoller.State.SCORE)); + m_driver.leftTrigger().and(isCoralMode.negate()).onTrue( + (m_clawRoller.getState() == ClawRoller.State.ALGAE_INTAKE) + ? m_clawRoller.setStateCommandNoEnd(ClawRoller.State.EJECT) + : m_clawRoller.setStateCommandNoEnd(ClawRoller.State.ALGAE_INTAKE)); // Driver Start Button: Climb Request (toggle) - m_driver.start().onTrue(Commands.runOnce(() -> { - m_profiledClimber.climbRequested = true; - m_profiledClimber.climbStep += 1; - })); + // m_driver.start().onTrue(Commands.runOnce(() -> { + // m_profiledClimber.climbRequested = true; + // m_profiledClimber.climbStep += 1; + // })); // Climb step 1: Get the Arm Down, then the Elevator down, and then and move climber to prep - m_profiledClimber.getClimbRequest().and(m_profiledClimber.getClimbStep1()).whileTrue( - Commands.parallel( - Commands.parallel( - m_profiledArm.setStateCommand(Arm.State.CLIMB), - Commands.waitUntil(() -> m_profiledArm.atPosition(0.1)) - .andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW))), - Commands - .waitUntil( - () -> m_profiledElevator.atPosition(0.1) && m_profiledArm.atPosition(0.1))) - .andThen(m_profiledClimber.setStateCommand(Climber.State.PREP))); + // m_profiledClimber.getClimbRequest().and(m_profiledClimber.getClimbStep1()).whileTrue( + // Commands.parallel( + // Commands.parallel( + // m_profiledArm.setStateCommand(Arm.State.CLIMB), + // Commands.waitUntil(() -> m_profiledArm.atPosition(0.1)) + // .andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW))), + // Commands + // .waitUntil( + // () -> m_profiledElevator.atPosition(0.1) && m_profiledArm.atPosition(0.1))) + // .andThen(m_profiledClimber.setStateCommand(Climber.State.PREP))); // Climb step 2: Move climber to climb - m_profiledClimber.getClimbRequest().and(m_profiledClimber.getClimbStep2()) - .whileTrue( - m_profiledClimber.setStateCommand(Climber.State.CLIMB) - .until(m_profiledClimber.getClimbedTrigger())); + // m_profiledClimber.getClimbRequest().and(m_profiledClimber.getClimbStep2()) + // .whileTrue( + // m_profiledClimber.setStateCommand(Climber.State.CLIMB) + // .until(m_profiledClimber.getClimbedTrigger())); - m_profiledClimber.getClimbedTrigger().onTrue(m_profiledClimber.climbedAlertCommand()); + // m_profiledClimber.getClimbedTrigger().onTrue(m_profiledClimber.climbedAlertCommand()); // Driver POV Right: End Climbing Sequence if needed - m_driver - .povRight() - .onTrue( - Commands.runOnce( - () -> { - m_profiledClimber.climbRequested = false; - m_profiledClimber.climbStep = 0; - })); + // m_driver + // .povRight() + // .onTrue( + // Commands.runOnce( + // () -> { + // m_profiledClimber.climbRequested = false; + // m_profiledClimber.climbStep = 0; + // })); // Slow drivetrain to 25% while climbing - m_profiledClimber.getClimbRequest().whileTrue( - DriveCommands.joystickDrive( - m_drive, - () -> -m_driver.getLeftY() * 0.25, - () -> -m_driver.getLeftX() * 0.25, - () -> -m_driver.getRightX() * 0.25)); + // m_profiledClimber.getClimbRequest().whileTrue( + // DriveCommands.joystickDrive( + // m_drive, + // () -> -m_driver.getLeftY() * 0.25, + // () -> -m_driver.getLeftX() * 0.25, + // () -> -m_driver.getRightX() * 0.25)); // Driver POV Down: Zero the Elevator (HOMING) m_driver.povDown().whileTrue( - m_profiledElevator.setStateCommand(Elevator.State.HOMING) - .until(m_profiledElevator.getHomedTrigger()) - .andThen(m_profiledElevator.zeroSensorCommand())); + Commands.sequence( + // Always move Arm to STOW position before moving Elevator + m_profiledArm.setStateCommand(Arm.State.STOW).until(() -> m_profiledArm.atPosition(0.1)), + // Move Elevator to homing position + Commands.waitUntil(() -> m_profiledArm.atPosition(0.1)) + .andThen(m_profiledElevator.setStateCommand(Elevator.State.HOMING) + .until(m_profiledElevator.getHomedTrigger())) + .andThen(m_profiledElevator.zeroSensorCommand()))); // Driver Right Bumper: Toggle between Coral and Algae Modes. // Make sure the Approach nearest reef face does not mess with this - m_driver.rightBumper() - .onTrue( - !m_driver.leftBumper().getAsBoolean() ? setCoralAlgaeModeCommand() - : Commands.runOnce(() -> { - })); + m_driver.rightBumper().and(m_driver.leftBumper().negate()) + .onTrue(setCoralAlgaeModeCommand()); } @@ -438,38 +476,23 @@ private void registerNamedCommands() // Go to the L1 Position NamedCommands.registerCommand( "L1", - Commands.parallel( - m_profiledElevator.setStateCommand(Elevator.State.LEVEL_1), - m_profiledArm.setStateCommand(Arm.State.LEVEL_1))); + m_superStruct.getTransitionCommand(Arm.State.LEVEL_1, Elevator.State.LEVEL_1)); // Go to the L2 Position NamedCommands.registerCommand( "L2", - Commands.parallel( - m_profiledElevator.setStateCommand(Elevator.State.LEVEL_2), - m_profiledArm.setStateCommand(Arm.State.LEVEL_2))); + m_superStruct.getTransitionCommand(Arm.State.LEVEL_2, Elevator.State.LEVEL_2)); // Go to the L3 Position NamedCommands.registerCommand( "L3", - Commands.parallel( - m_profiledElevator.setStateCommand(Elevator.State.LEVEL_3), - m_profiledArm.setStateCommand(Arm.State.LEVEL_3))); + m_superStruct.getTransitionCommand(Arm.State.LEVEL_3, Elevator.State.LEVEL_3)); // Go to the L4 Position NamedCommands.registerCommand( "L4", - Commands.parallel( - m_profiledElevator.setStateCommand(Elevator.State.LEVEL_4), - Commands.waitUntil(() -> m_profiledElevator.atPosition(1)) - .andThen(m_profiledArm.setStateCommand(Arm.State.LEVEL_4)))); + m_superStruct.getTransitionCommand(Arm.State.LEVEL_4, Elevator.State.LEVEL_4)); // Go to the Home Position NamedCommands.registerCommand( "Home", - Commands.parallel( - m_profiledElevator.setStateCommand(Elevator.State.STOW), - m_profiledArm.setStateCommand(Arm.State.STOW))); - - // Wait for intake laserCAN to be triggered - NamedCommands.registerCommand("WaitForCoral", - Commands.waitUntil(m_intakeLaserCAN.triggered)); + m_superStruct.getTransitionCommand(Arm.State.STOW, Elevator.State.STOW)); // Wait for intake laserCAN to be triggered NamedCommands.registerCommand("WaitForCoral", @@ -478,23 +501,12 @@ private void registerNamedCommands() // Intake Coral NamedCommands.registerCommand( "IntakeCoral", - m_clawRoller.setStateCommand(ClawRoller.State.INTAKE) - .until(m_clawRollerLaserCAN.triggered) - .andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.HOLDCORAL)) - .andThen(Commands.waitUntil(() -> m_clawRoller.atPosition(1)))); - - // Intake Algae - NamedCommands.registerCommand( - "IntakeAlgae", - Commands.sequence( - (FieldConstants.getNearestReefBranch(m_drive.getPose(), ReefSide.RIGHT) - .getTranslation().getX() > 0) - ? m_profiledElevator.setStateCommand(Elevator.State.ALGAE_HIGH) - : m_profiledElevator.setStateCommand(Elevator.State.ALGAE_LOW), - m_clawRoller.setStateCommand(ClawRoller.State.INTAKE), - Commands.waitUntil(m_clawRoller.stalled) - .andThen(m_clawRoller.setStateCommand(ClawRoller.State.OFF))) - .andThen(m_profiledElevator.setStateCommand(Elevator.State.STOW))); + Commands.parallel( + m_superStruct.getTransitionCommand(Arm.State.CORAL_INTAKE, Elevator.State.CORAL_INTAKE), + m_clawRoller.setStateCommand(ClawRoller.State.INTAKE) + .until(m_clawRollerLaserCAN.triggered) + .andThen(m_clawRoller.setStateCommandNoEnd(ClawRoller.State.HOLDCORAL)) + .andThen(Commands.waitUntil(() -> m_clawRoller.atPosition(1))))); NamedCommands.registerCommand( "Score", diff --git a/src/main/java/frc/robot/commands/DriveCommands.java b/src/main/java/frc/robot/commands/DriveCommands.java index 7970295..72ff42c 100644 --- a/src/main/java/frc/robot/commands/DriveCommands.java +++ b/src/main/java/frc/robot/commands/DriveCommands.java @@ -37,6 +37,7 @@ import java.util.List; import java.util.function.DoubleSupplier; import java.util.function.Supplier; +import org.littletonrobotics.junction.Logger; public class DriveCommands { private static final double DEADBAND = 0.1; @@ -227,6 +228,7 @@ public static Command joystickApproach( .plus(offsetVector); SmartDashboard.putData(alignController); // TODO: Calibrate PID + Logger.recordOutput("AlignDebug/approachTarget", approachTranslation); // Calculate angular speed double omega = @@ -240,15 +242,10 @@ public static Command joystickApproach( linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec(), linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec(), omega); - boolean isFlipped = - DriverStation.getAlliance().isPresent() - && DriverStation.getAlliance().get() == Alliance.Red; drive.runVelocity( ChassisSpeeds.fromFieldRelativeSpeeds( speeds, - isFlipped - ? drive.getRotation().plus(new Rotation2d(Math.PI)) - : drive.getRotation())); + drive.getRotation())); }, drive) diff --git a/src/main/java/frc/robot/generated/TunerConstants.java b/src/main/java/frc/robot/generated/TunerConstants.java index 807f5f6..eff43c1 100644 --- a/src/main/java/frc/robot/generated/TunerConstants.java +++ b/src/main/java/frc/robot/generated/TunerConstants.java @@ -80,7 +80,7 @@ public class TunerConstants { // CAN bus that the devices are located on; // All swerve devices must share the same CAN bus - public static final CANBus kCANBus = new CANBus("", "./logs/example.hoot"); + public static final CANBus kCANBus = new CANBus("Drivetrain", "./logs/example.hoot"); // Theoretical free speed (m/s) at 12 V applied output; // This needs to be tuned to your individual robot @@ -97,7 +97,7 @@ public class TunerConstants { private static final boolean kInvertLeftSide = false; private static final boolean kInvertRightSide = true; - private static final int kPigeonId = 13; + private static final int kPigeonId = 1; // These are only used for simulation private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01); @@ -136,9 +136,9 @@ public class TunerConstants { .withDriveFrictionVoltage(kDriveFrictionVoltage); // Front Left - private static final int kFrontLeftDriveMotorId = 1; - private static final int kFrontLeftSteerMotorId = 2; - private static final int kFrontLeftEncoderId = 9; + private static final int kFrontLeftDriveMotorId = 11; + private static final int kFrontLeftSteerMotorId = 9; + private static final int kFrontLeftEncoderId = 10; private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.393798828125); private static final boolean kFrontLeftSteerMotorInverted = false; private static final boolean kFrontLeftEncoderInverted = true; @@ -147,9 +147,9 @@ public class TunerConstants { private static final Distance kFrontLeftYPos = Inches.of(9.5); // Front Right - private static final int kFrontRightDriveMotorId = 5; - private static final int kFrontRightSteerMotorId = 6; - private static final int kFrontRightEncoderId = 10; + private static final int kFrontRightDriveMotorId = 7; + private static final int kFrontRightSteerMotorId = 5; + private static final int kFrontRightEncoderId = 6; private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.267822265625); private static final boolean kFrontRightSteerMotorInverted = false; private static final boolean kFrontRightEncoderInverted = true; @@ -158,9 +158,9 @@ public class TunerConstants { private static final Distance kFrontRightYPos = Inches.of(-9.5); // Back Left - private static final int kBackLeftDriveMotorId = 3; - private static final int kBackLeftSteerMotorId = 4; - private static final int kBackLeftEncoderId = 11; + private static final int kBackLeftDriveMotorId = 14; + private static final int kBackLeftSteerMotorId = 12; + private static final int kBackLeftEncoderId = 13; private static final Angle kBackLeftEncoderOffset = Rotations.of(0.106689453125); private static final boolean kBackLeftSteerMotorInverted = false; private static final boolean kBackLeftEncoderInverted = true; @@ -169,9 +169,9 @@ public class TunerConstants { private static final Distance kBackLeftYPos = Inches.of(9.5); // Back Right - private static final int kBackRightDriveMotorId = 7; - private static final int kBackRightSteerMotorId = 8; - private static final int kBackRightEncoderId = 12; + private static final int kBackRightDriveMotorId = 4; + private static final int kBackRightSteerMotorId = 2; + private static final int kBackRightEncoderId = 3; private static final Angle kBackRightEncoderOffset = Rotations.of(0.0048828125); private static final boolean kBackRightSteerMotorInverted = false; private static final boolean kBackRightEncoderInverted = true; diff --git a/src/main/java/frc/robot/subsystems/Arm/Arm.java b/src/main/java/frc/robot/subsystems/Arm/Arm.java index f3ee441..9d46f60 100644 --- a/src/main/java/frc/robot/subsystems/Arm/Arm.java +++ b/src/main/java/frc/robot/subsystems/Arm/Arm.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.Arm; +import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.Logger; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.Timer; @@ -16,27 +17,32 @@ @Getter public class Arm extends GenericMotionProfiledSubsystem { + static LoggedTunableNumber positionTuning = + new LoggedTunableNumber("Arm/PositionTuningSP", 124.0); + + // .14 rot is the max extension + @RequiredArgsConstructor @Getter public enum State implements TargetState { // HOMING(0.0, 0.0, ProfileType.MM_POSITION), - STOW(Units.degreesToRotations(20.0), 0.0, ProfileType.MM_POSITION), - CORAL_INTAKE(Units.degreesToRotations(0.0), 0.0, ProfileType.MM_POSITION), - LEVEL_1(Units.degreesToRotations(20.0), 0.0, ProfileType.MM_POSITION), - LEVEL_2(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - LEVEL_3(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - LEVEL_4(Units.degreesToRotations(60.0), 0.0, ProfileType.MM_POSITION), - CLIMB(Units.degreesToRotations(95.0), 0.0, ProfileType.MM_POSITION), - ALGAE_LOW(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - ALGAE_HIGH(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - ALGAE_GROUND(Units.degreesToRotations(105.0), 0.0, ProfileType.MM_POSITION), - ALGAE_SCORE(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - BARGE(Units.degreesToRotations(30.0), 0.0, ProfileType.MM_POSITION), - CHARACTERIZATION(0.0, 0.0, ProfileType.CHARACTERIZATION); - - private final double output; - private final double feedFwd; + STOW(() -> Units.degreesToRotations(124.0), ProfileType.MM_POSITION), + CORAL_INTAKE(() -> 0.42, ProfileType.MM_POSITION), + LEVEL_1(() -> Units.degreesToRotations(120.0), ProfileType.MM_POSITION), + LEVEL_2(() -> Units.degreesToRotations(105.0), ProfileType.MM_POSITION), + LEVEL_3(() -> Units.degreesToRotations(105.0), ProfileType.MM_POSITION), + LEVEL_4(() -> Units.degreesToRotations(90.0), ProfileType.MM_POSITION), + CLIMB(() -> Units.degreesToRotations(50.4), ProfileType.MM_POSITION), + ALGAE_LOW(() -> Units.degreesToRotations(114.0), ProfileType.MM_POSITION), + ALGAE_HIGH(() -> Units.degreesToRotations(114.0), ProfileType.MM_POSITION), + ALGAE_GROUND(() -> Units.degreesToRotations(9.0), ProfileType.MM_POSITION), + ALGAE_SCORE(() -> Units.degreesToRotations(114.0), ProfileType.MM_POSITION), + BARGE(() -> Units.degreesToRotations(30.0), ProfileType.MM_POSITION), + TUNING(() -> Units.degreesToRotations(positionTuning.getAsDouble()), + ProfileType.MM_POSITION), + CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION); + private final DoubleSupplier output; private final ProfileType profileType; } @@ -58,7 +64,7 @@ public Arm(ArmIO io, boolean isSim) /** Constructor */ public Command setStateCommand(State state) { - return runOnce(() -> this.state = state); + return this.runOnce(() -> this.state = state); } public boolean atPosition(double tolerance) diff --git a/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRoller.java b/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRoller.java index 22a8c71..c401361 100644 --- a/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRoller.java +++ b/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRoller.java @@ -1,9 +1,11 @@ package frc.robot.subsystems.Claw.ClawRoller; +import java.util.function.DoubleSupplier; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.subsystems.GenericMotionProfiledSubsystem.GenericMotionProfiledSubsystem; import frc.robot.subsystems.GenericMotionProfiledSubsystem.GenericMotionProfiledSubsystem.TargetState; +import frc.robot.util.LoggedTunableNumber; import frc.robot.util.Util; import lombok.Getter; import lombok.RequiredArgsConstructor; @@ -14,23 +16,24 @@ public class ClawRoller extends GenericMotionProfiledSubsystem { - public final Trigger stalled = new Trigger(() -> super.inputs.supplyCurrentAmps[0] < 1); // TODO: - // real - // numbers + public final Trigger stalled = new Trigger(() -> super.inputs.torqueCurrentAmps[0] >= 30); + + static LoggedTunableNumber holdCoralSP = new LoggedTunableNumber("ClawRoller/HoldCoralSP", 0.0); + static LoggedTunableNumber algaeIntakeSP = new LoggedTunableNumber("ClawRoller/AlgaeIntakeSP", -15.0); @RequiredArgsConstructor @Getter public enum State implements TargetState { - OFF(0.0, 0.0, ProfileType.OPEN_VOLTAGE), // TODO: tune on real robot - INTAKE(6.0, 0.0, ProfileType.OPEN_VOLTAGE), - EJECT(-6.0, 0.0, ProfileType.OPEN_VOLTAGE), - SCORE(6.0, 0.0, ProfileType.OPEN_VOLTAGE), - HOLDCORAL(1.0, 0.0, ProfileType.MM_POSITION); // One rotation after detecting coral, switch - // to HOLDCORAL to tell the motors to go one - // rotaiton - - private final double output; - private final double feedFwd; + OFF(() -> 0.0, ProfileType.OPEN_VOLTAGE), // TODO: tune on real robot + INTAKE(() -> 2.0, ProfileType.OPEN_VOLTAGE), + INTAKESLOW(() -> 1, ProfileType.OPEN_VOLTAGE), + SHUFFLE(() -> -0.5, ProfileType.OPEN_VOLTAGE), + EJECT(() -> 6.0, ProfileType.OPEN_VOLTAGE), + SCORE(() -> 8.0, ProfileType.OPEN_VOLTAGE), + HOLDCORAL(() -> holdCoralSP.getAsDouble(), ProfileType.MM_POSITION), + ALGAE_INTAKE(() -> algaeIntakeSP.getAsDouble(), ProfileType.OPEN_CURRENT); + + private final DoubleSupplier output; private final ProfileType profileType; } @@ -55,6 +58,7 @@ public Command setStateCommandNoEnd(State state) public boolean atPosition(double tolerance) { - return Util.epsilonEquals(io.getPosition(), state.output, Math.max(0.0001, tolerance)); + return Util.epsilonEquals(io.getPosition(), state.output.getAsDouble(), + Math.max(0.0001, tolerance)); } } diff --git a/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRollerConstants.java b/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRollerConstants.java index ce206bf..6fb40d6 100644 --- a/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRollerConstants.java +++ b/src/main/java/frc/robot/subsystems/Claw/ClawRoller/ClawRollerConstants.java @@ -41,15 +41,15 @@ public final class ClawRollerConstants { kSubSysConstants.kMotorConfig.CurrentLimits.StatorCurrentLimitEnable = true; /* REAL system profile constants */ - kSubSysConstants.kMotorConfig.Slot0.kP = 0; // TODO: tune on real robot + kSubSysConstants.kMotorConfig.Slot0.kP = 50; // TODO: tune on real robot kSubSysConstants.kMotorConfig.Slot0.kI = 0; kSubSysConstants.kMotorConfig.Slot0.kD = 0; kSubSysConstants.kMotorConfig.Slot0.kG = 0; kSubSysConstants.kMotorConfig.Slot0.kS = 0; kSubSysConstants.kMotorConfig.Slot0.kV = 0; kSubSysConstants.kMotorConfig.Slot0.kA = 0; - kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 0; - kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicAcceleration = 0; + kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 100; + kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicAcceleration = 10; kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicJerk = 0; /* SIM system profile constants */ diff --git a/src/main/java/frc/robot/subsystems/Claw/ClawRollerLaserCAN/ClawRollerLaserCAN.java b/src/main/java/frc/robot/subsystems/Claw/ClawRollerLaserCAN/ClawRollerLaserCAN.java index eecaddf..0f7142b 100644 --- a/src/main/java/frc/robot/subsystems/Claw/ClawRollerLaserCAN/ClawRollerLaserCAN.java +++ b/src/main/java/frc/robot/subsystems/Claw/ClawRollerLaserCAN/ClawRollerLaserCAN.java @@ -16,7 +16,7 @@ public class ClawRollerLaserCAN extends GenericLaserCANSubsystem { + static LoggedTunableNumber positionTuning = new LoggedTunableNumber("Climber/PositionTuningSP", 0.0); + @RequiredArgsConstructor @Getter public enum State implements TargetState { // HOME is climber upright, Prep - Assuming that PREP position is parallel to the x axis, CLIMB is inwards - HOME(Units.degreesToRotations(90), 0.0, ProfileType.MM_POSITION), - PREP(Units.degreesToRotations(0.0), 0.0, ProfileType.MM_POSITION), - CLIMB(Units.degreesToRotations(110.0), 0.0, ProfileType.MM_POSITION); + HOME(() -> Units.degreesToRotations(90.0), ProfileType.MM_POSITION), + PREP(() -> Units.degreesToRotations(0.0), ProfileType.MM_POSITION), + CLIMB(() -> Units.degreesToRotations(110.0), ProfileType.MM_POSITION), + TUNING(() -> Units.degreesToRotations(positionTuning.getAsDouble()), ProfileType.MM_POSITION), + ; - private final double output; - private final double feedFwd; + private final DoubleSupplier output; private final ProfileType profileType; } diff --git a/src/main/java/frc/robot/subsystems/Elevator/Elevator.java b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java index 86bb210..30467fa 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.Elevator; +import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.Logger; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.filter.Debouncer.DebounceType; @@ -21,27 +22,32 @@ @Getter public class Elevator extends GenericMotionProfiledSubsystem { + static LoggedTunableNumber homingTuning = + new LoggedTunableNumber("Elevator/HomingVoltageSP", -0.2); + static LoggedTunableNumber positionTuning = + new LoggedTunableNumber("Elevator/PositionTuningSP", 0.05); + @RequiredArgsConstructor @Getter public enum State implements TargetState { - HOMING(-0.2, 0.0, ProfileType.OPEN_VOLTAGE), + HOMING(() -> homingTuning.getAsDouble(), ProfileType.OPEN_VOLTAGE), // TODO: Test Voltage and position values (rotations) - STOW(0.15, 0.0, ProfileType.MM_POSITION), - CORAL_INTAKE(0.05, 0.0, ProfileType.MM_POSITION), - LEVEL_1(0.2, 0.0, ProfileType.MM_POSITION), - LEVEL_2(1, 0.0, ProfileType.MM_POSITION), - LEVEL_3(2, 0.0, ProfileType.MM_POSITION), - LEVEL_4(3.75, 0.0, ProfileType.MM_POSITION), - CLIMB(0.05, 0.0, ProfileType.MM_POSITION), - ALGAE_LOW(0.8, 0.0, ProfileType.MM_POSITION), - ALGAE_HIGH(1.5, 0.0, ProfileType.MM_POSITION), - ALGAE_GROUND(0.05, 0.0, ProfileType.MM_POSITION), - ALGAE_SCORE(0.05, 0.0, ProfileType.MM_POSITION), - BARGE(4.0, 0.0, ProfileType.MM_POSITION), - CHARACTERIZATION(0.0, 0.0, ProfileType.CHARACTERIZATION); - - private final double output; - private final double feedFwd; + STOW(() -> 0, ProfileType.MM_POSITION), + CORAL_INTAKE(() -> 0, ProfileType.MM_POSITION), + LEVEL_1(() -> 0.2, ProfileType.MM_POSITION), + LEVEL_2(() -> 1.4, ProfileType.MM_POSITION), + LEVEL_3(() -> 2.85, ProfileType.MM_POSITION), + LEVEL_4(() -> 5.20, ProfileType.MM_POSITION), + CLIMB(() -> 0.05, ProfileType.MM_POSITION), + ALGAE_LOW(() -> 0.8, ProfileType.MM_POSITION), + ALGAE_HIGH(() -> 1.5, ProfileType.MM_POSITION), + ALGAE_GROUND(() -> 0.05, ProfileType.MM_POSITION), + ALGAE_SCORE(() -> 0.05, ProfileType.MM_POSITION), + BARGE(() -> 4.0, ProfileType.MM_POSITION), + TUNING(() -> positionTuning.getAsDouble(), ProfileType.MM_POSITION), + CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION); + + private final DoubleSupplier output; private final ProfileType profileType; } @@ -64,7 +70,7 @@ public Elevator(ElevatorIO io, boolean isSim) public Command setStateCommand(State state) { - return runOnce(() -> this.state = state); + return this.runOnce(() -> this.state = state); } private Debouncer homedDebouncer = new Debouncer(.25, DebounceType.kRising); diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorConstants.java index 11fbe77..7fdd71d 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorConstants.java @@ -31,13 +31,13 @@ public final class ElevatorConstants { kSubSysConstants.kLeaderMotor = Ports.ELEVATOR_MAIN; kSubSysConstants.kFollowMotor = Ports.ELEVATOR_FOLLOWER; - kSubSysConstants.kFollowerOpposesMain = true; + kSubSysConstants.kFollowerOpposesMain = false; // Using TalonFX internal encoder kSubSysConstants.kCANcoder = null; kSubSysConstants.kMotorConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor; - kSubSysConstants.kMotorConfig.Feedback.SensorToMechanismRatio = 1.0; + kSubSysConstants.kMotorConfig.Feedback.SensorToMechanismRatio = 9.6; kSubSysConstants.kMotorConfig.Feedback.RotorToSensorRatio = 1.0; // Using a remote CANcoder @@ -56,7 +56,7 @@ public final class ElevatorConstants { kSubSysConstants.kMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; kSubSysConstants.kMotorConfig.MotorOutput.Inverted = - InvertedValue.CounterClockwise_Positive; + InvertedValue.Clockwise_Positive; kSubSysConstants.kMotorConfig.Voltage.PeakForwardVoltage = 12.0; kSubSysConstants.kMotorConfig.Voltage.PeakReverseVoltage = -12.0; @@ -65,17 +65,20 @@ public final class ElevatorConstants { kSubSysConstants.kMotorConfig.CurrentLimits.StatorCurrentLimit = 70; kSubSysConstants.kMotorConfig.CurrentLimits.StatorCurrentLimitEnable = true; + kSubSysConstants.kMotorConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = 5.4; + kSubSysConstants.kMotorConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; + /* REAL system profile constants */ - kSubSysConstants.kMotorConfig.Slot0.kP = 0; + kSubSysConstants.kMotorConfig.Slot0.kP = 1200; kSubSysConstants.kMotorConfig.Slot0.kI = 0; - kSubSysConstants.kMotorConfig.Slot0.kD = 0; + kSubSysConstants.kMotorConfig.Slot0.kD = 30; kSubSysConstants.kMotorConfig.Slot0.GravityType = GravityTypeValue.Elevator_Static; - kSubSysConstants.kMotorConfig.Slot0.kG = 0; + kSubSysConstants.kMotorConfig.Slot0.kG = 5; kSubSysConstants.kMotorConfig.Slot0.kS = 0; kSubSysConstants.kMotorConfig.Slot0.kV = 0; kSubSysConstants.kMotorConfig.Slot0.kA = 0; - kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 0; - kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicAcceleration = 0; + kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 75; + kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicAcceleration = 20; kSubSysConstants.kMotorConfig.MotionMagic.MotionMagicJerk = 0; /* SIM system profile constants */ diff --git a/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/GenericLaserCANSubsystemIOImpl.java b/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/GenericLaserCANSubsystemIOImpl.java index e7ac4a8..787e9c2 100644 --- a/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/GenericLaserCANSubsystemIOImpl.java +++ b/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/GenericLaserCANSubsystemIOImpl.java @@ -18,6 +18,8 @@ public class GenericLaserCANSubsystemIOImpl implements GenericLaserCANSubsystemI private LaserCanInterface lc = null; private String name; + private int tries = 0; + private boolean hasConfiged = false; private Distance currentDistance; @@ -37,17 +39,22 @@ public GenericLaserCANSubsystemIOImpl( lc = isSim ? new LaserCANSim(name) : new LaserCan(constants.laserCANDeviceId.getDeviceNumber()); - - try { - lc.setRangingMode(constants.rangingMode); - lc.setRegionOfInterest(constants.regionOfInterest); - lc.setTimingBudget(constants.timingBudget); - failedConfig.set(false); - } catch (ConfigurationFailedException e) { - System.out.println("Configuration failed! " + e); - failedConfig.setText("Failed to configure " + name + "!"); - failedConfig.set(true); + while (!hasConfiged && tries < 5) { + try { + lc.setRangingMode(constants.rangingMode); + lc.setRegionOfInterest(constants.regionOfInterest); + lc.setTimingBudget(constants.timingBudget); + failedConfig.set(false); + System.out.println("Succesfully configured " + name); + hasConfiged = true; + } catch (ConfigurationFailedException e) { + System.out.println("Configuration failed for " + name + "! " + e); + failedConfig.setText("Failed to configure " + name + "!"); + failedConfig.set(true); + tries++; + } } + } public Distance getMeasurement() diff --git a/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/LaserCANSim.java b/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/LaserCANSim.java index c99f905..c38a3eb 100644 --- a/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/LaserCANSim.java +++ b/src/main/java/frc/robot/subsystems/GenericLaserCANSubsystem/LaserCANSim.java @@ -14,7 +14,7 @@ public class LaserCANSim implements LaserCanInterface { public LaserCANSim(String name) { - tunableDistance = new LoggedTunableNumber(name + "/Measurement", 0); + tunableDistance = new LoggedTunableNumber(name + "/Measurement", Double.POSITIVE_INFINITY); } @Override diff --git a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystem.java b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystem.java index a2c8928..28ce837 100644 --- a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystem.java +++ b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystem.java @@ -5,6 +5,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; import frc.robot.util.LoggedTunableNumber; +import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.Logger; public abstract class GenericMotionProfiledSubsystem @@ -20,13 +21,13 @@ public enum ProfileType { MM_VELOCITY, OPEN_VOLTAGE, OPEN_CURRENT, + DISABLED_COAST, + DISABLED_BRAKE, CHARACTERIZATION } public interface TargetState { - public double getOutput(); - - public double getFeedFwd(); + public DoubleSupplier getOutput(); public ProfileType getProfileType(); } @@ -133,27 +134,35 @@ public void periodic() default: case POSITION: /* Run Closed Loop to position in rotations */ - io.runToPosition(getState().getOutput(), getState().getFeedFwd()); + io.runToPosition(getState().getOutput().getAsDouble()); break; case VELOCITY: /* Run Closed Loop to velocity in rotations/second */ - io.runToVelocity(getState().getOutput(), getState().getFeedFwd()); + io.runToVelocity(getState().getOutput().getAsDouble()); break; case MM_POSITION: /* Run Motion Magic to the specified position setpoint (in rotations) */ - io.runMotionMagicPosition(getState().getOutput(), getState().getFeedFwd()); + io.runMotionMagicPosition(getState().getOutput().getAsDouble()); break; case MM_VELOCITY: /* Run Motion Magic to the specified velocity setpoint (in rotations/second) */ - io.runMotionMagicVelocity(getState().getOutput(), getState().getFeedFwd()); + io.runMotionMagicVelocity(getState().getOutput().getAsDouble()); break; case OPEN_VOLTAGE: /* Run Open Loop using specified voltage in volts */ - io.runVoltage(getState().getOutput()); + io.runVoltage(getState().getOutput().getAsDouble()); break; case OPEN_CURRENT: /* Run Open Loop using specified current in amps */ - io.runCurrent(getState().getOutput()); + io.runCurrent(getState().getOutput().getAsDouble()); + break; + case DISABLED_COAST: + /* Stop all output and put motor in Coast mode */ + io.stopCoast(); + break; + case DISABLED_BRAKE: + /* Stop all output and put motor in Brake mode */ + io.stopBrake(); break; case CHARACTERIZATION: /* diff --git a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIO.java b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIO.java index 1e7b6cd..5e87be2 100644 --- a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIO.java +++ b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIO.java @@ -38,19 +38,27 @@ public default void runCurrent(double amps) {} /** Run Closed Loop to position in rotations */ - public default void runToPosition(double position, double feedforward) + public default void runToPosition(double position) {} /** Run Closed Loop to velocity in rotations/second */ - public default void runToVelocity(double velocity, double feedforward) + public default void runToVelocity(double velocity) {} /** Run Motion Magic to the specified setpoint */ - public default void runMotionMagicPosition(double setpoint, double feedFwd) + public default void runMotionMagicPosition(double setpoint) {} /** Run Motion Magic to the specified velocity */ - public default void runMotionMagicVelocity(double velocity, double feedFwd) + public default void runMotionMagicVelocity(double velocity) + {} + + /* Stop in Coast mode */ + public default void stopCoast() + {} + + /* Stop in Brake mode */ + public default void stopBrake() {} /* Stop in Open Loop */ diff --git a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIOImpl.java b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIOImpl.java index dad5ad3..aaa9c94 100644 --- a/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIOImpl.java +++ b/src/main/java/frc/robot/subsystems/GenericMotionProfiledSubsystem/GenericMotionProfiledSubsystemIOImpl.java @@ -3,10 +3,12 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.CoastOut; import com.ctre.phoenix6.controls.Follower; import com.ctre.phoenix6.controls.MotionMagicTorqueCurrentFOC; import com.ctre.phoenix6.controls.MotionMagicVelocityTorqueCurrentFOC; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +import com.ctre.phoenix6.controls.StaticBrake; import com.ctre.phoenix6.controls.TorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; import com.ctre.phoenix6.controls.VoltageOut; @@ -87,6 +89,8 @@ public class GenericMotionProfiledSubsystemIOImpl implements GenericMotionProfil new MotionMagicTorqueCurrentFOC(0.0).withUpdateFreqHz(0.0).withSlot(0); private final MotionMagicVelocityTorqueCurrentFOC motionMagicVelocityControl = new MotionMagicVelocityTorqueCurrentFOC(0.0).withUpdateFreqHz(0.0).withSlot(0); + private final CoastOut coastOut = new CoastOut(); + private final StaticBrake staticBrake = new StaticBrake(); /* * Constructor @@ -350,35 +354,49 @@ public void runCurrent(double amps) /** Run Closed Loop to setpoint in rotations */ @Override - public void runToPosition(double position, double feedFwd) + public void runToPosition(double position) { - mMainMotor.setControl(positionControl.withPosition(position).withFeedForward(feedFwd)); + mMainMotor.setControl(positionControl.withPosition(position)); mOpSetpoint = position; } /** Run Closed Loop to velocity in rotations/second */ @Override - public void runToVelocity(double velocity, double feedFwd) + public void runToVelocity(double velocity) { - mMainMotor.setControl(velocityControl.withVelocity(velocity).withFeedForward(feedFwd)); + mMainMotor.setControl(velocityControl.withVelocity(velocity)); mOpSetpoint = velocity; } /** Run Motion Magic to the specified setpoint */ @Override - public void runMotionMagicPosition(double setpoint, double feedFwd) + public void runMotionMagicPosition(double setpoint) { mMainMotor.setControl( - motionMagicPositionControl.withPosition(setpoint).withFeedForward(feedFwd)); + motionMagicPositionControl.withPosition(setpoint)); mOpSetpoint = setpoint; } /** Run Motion Magic Velocity to the specified velocity */ @Override - public void runMotionMagicVelocity(double velocity, double feedFwd) + public void runMotionMagicVelocity(double velocity) { mMainMotor.setControl( - motionMagicVelocityControl.withVelocity(velocity).withFeedForward(feedFwd)); + motionMagicVelocityControl.withVelocity(velocity)); + } + + /* Stop in Coast mode */ + @Override + public void stopCoast() + { + mMainMotor.setControl(coastOut); + } + + /* Stop in Brake mode */ + @Override + public void stopBrake() + { + mMainMotor.setControl(staticBrake); } /* Stop in Open Loop */ diff --git a/src/main/java/frc/robot/subsystems/Superstructure.java b/src/main/java/frc/robot/subsystems/Superstructure.java index ec65e5c..e50882d 100644 --- a/src/main/java/frc/robot/subsystems/Superstructure.java +++ b/src/main/java/frc/robot/subsystems/Superstructure.java @@ -43,10 +43,12 @@ public Command getTransitionCommand(Arm.State armState, Elevator.State elevatorS // Always move Arm to STOW position before moving Elevator m_Arm.setStateCommand(Arm.State.STOW).until(() -> m_Arm.atPosition(armTolerance)), // Move Elevator to new position - m_Elevator.setStateCommand(elevatorState) - .until(() -> m_Elevator.atPosition(elevTolerance)), + Commands.waitUntil(() -> m_Arm.atPosition(armTolerance)) + .andThen(m_Elevator.setStateCommand(elevatorState) + .until(() -> m_Elevator.atPosition(elevTolerance))), // Reposition Arm to new position - m_Arm.setStateCommand(armState).until(() -> m_Arm.atPosition(armTolerance)))); + Commands.waitUntil(() -> m_Elevator.atPosition(elevTolerance)).andThen( + m_Arm.setStateCommand(armState).until(() -> m_Arm.atPosition(armTolerance))))); } /** diff --git a/src/main/java/frc/robot/subsystems/Vision/VisionConstants.java b/src/main/java/frc/robot/subsystems/Vision/VisionConstants.java index 91c2130..e326c6f 100644 --- a/src/main/java/frc/robot/subsystems/Vision/VisionConstants.java +++ b/src/main/java/frc/robot/subsystems/Vision/VisionConstants.java @@ -31,9 +31,10 @@ public class VisionConstants { // Robot to camera transforms // (Not used by Limelight, configure in web UI instead) public static Transform3d robotToCamera0 = - new Transform3d(0.287, 0.260, 0.211, new Rotation3d(0.0, Units.degreesToRadians(-15), 0.0)); + new Transform3d(0.289591, 0.261649, 0.205829, + new Rotation3d(0.0, Units.degreesToRadians(-15), 0.0)); public static Transform3d robotToCamera1 = - new Transform3d(0.287, -0.260, 0.211, + new Transform3d(0.289591, -0.261649, 0.205829, new Rotation3d(0.0, Units.degreesToRadians(-15), 0.0)); // Basic filtering thresholds diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index fa81b2f..c587313 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,35 +1,35 @@ { - "fileName": "AdvantageKit.json", - "name": "AdvantageKit", - "version": "4.1.0", - "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", - "frcYear": "2025", - "mavenUrls": [ - "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" - ], - "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", - "javaDependencies": [ - { - "groupId": "org.littletonrobotics.akit", - "artifactId": "akit-java", - "version": "4.1.0" - } - ], - "jniDependencies": [ - { - "groupId": "org.littletonrobotics.akit", - "artifactId": "akit-wpilibio", - "version": "4.1.0", - "skipInvalidPlatforms": false, - "isJar": false, - "validPlatforms": [ - "linuxathena", - "linuxx86-64", - "linuxarm64", - "osxuniversal", - "windowsx86-64" - ] - } - ], - "cppDependencies": [] -} + "fileName": "AdvantageKit.json", + "name": "AdvantageKit", + "version": "4.1.1", + "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", + "frcYear": "2025", + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" + ], + "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-java", + "version": "4.1.1" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-wpilibio", + "version": "4.1.1", + "skipInvalidPlatforms": false, + "isJar": false, + "validPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + } + ], + "cppDependencies": [] +} \ No newline at end of file diff --git a/vendordeps/PathplannerLib-2025.2.2.json b/vendordeps/PathplannerLib-2025.2.3.json similarity index 87% rename from vendordeps/PathplannerLib-2025.2.2.json rename to vendordeps/PathplannerLib-2025.2.3.json index a5bf9ee..9151ce4 100644 --- a/vendordeps/PathplannerLib-2025.2.2.json +++ b/vendordeps/PathplannerLib-2025.2.3.json @@ -1,7 +1,7 @@ { - "fileName": "PathplannerLib-2025.2.2.json", + "fileName": "PathplannerLib-2025.2.3.json", "name": "PathplannerLib", - "version": "2025.2.2", + "version": "2025.2.3", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2025", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.2.2" + "version": "2025.2.3" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.2.2", + "version": "2025.2.3", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Phoenix6-25.2.1.json b/vendordeps/Phoenix6-25.2.1.json deleted file mode 100644 index 349f124..0000000 --- a/vendordeps/Phoenix6-25.2.1.json +++ /dev/null @@ -1,419 +0,0 @@ -{ - "fileName": "Phoenix6-25.2.1.json", - "name": "CTRE-Phoenix (v6)", - "version": "25.2.1", - "frcYear": "2025", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "25.2.1" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "25.2.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "25.2.1", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.2.1", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.2.1", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "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": "25.2.1", - "libName": "CTRE_SimProCANrange", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} diff --git a/vendordeps/Phoenix6-25.2.2.json b/vendordeps/Phoenix6-25.2.2.json new file mode 100644 index 0000000..d617643 --- /dev/null +++ b/vendordeps/Phoenix6-25.2.2.json @@ -0,0 +1,419 @@ +{ + "fileName": "Phoenix6-25.2.2.json", + "name": "CTRE-Phoenix (v6)", + "version": "25.2.2", + "frcYear": "2025", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "25.2.2" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "25.2.2", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.2.2", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.2.2", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "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": "25.2.2", + "libName": "CTRE_SimProCANrange", + "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/libgrapplefrc2025.json b/vendordeps/libgrapplefrc2025.json index a711280..f593245 100644 --- a/vendordeps/libgrapplefrc2025.json +++ b/vendordeps/libgrapplefrc2025.json @@ -1,74 +1,74 @@ { - "fileName": "libgrapplefrc2025.json", - "name": "libgrapplefrc", - "version": "2025.0.8", - "frcYear": "2025", - "uuid": "8ef3423d-9532-4665-8339-206dae1d7168", - "mavenUrls": [ - "https://storage.googleapis.com/grapple-frc-maven" - ], - "jsonUrl": "https://storage.googleapis.com/grapple-frc-maven/libgrapplefrc2025.json", - "javaDependencies": [ - { - "groupId": "au.grapplerobotics", - "artifactId": "libgrapplefrcjava", - "version": "2025.0.8" - } - ], - "jniDependencies": [ - { - "groupId": "au.grapplerobotics", - "artifactId": "libgrapplefrcdriver", - "version": "2025.0.8", - "skipInvalidPlatforms": true, - "isJar": false, - "validPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ], - "cppDependencies": [ - { - "groupId": "au.grapplerobotics", - "artifactId": "libgrapplefrccpp", - "version": "2025.0.8", - "libName": "grapplefrc", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - }, - { - "groupId": "au.grapplerobotics", - "artifactId": "libgrapplefrcdriver", - "version": "2025.0.8", - "libName": "grapplefrcdriver", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ] -} + "fileName": "libgrapplefrc2025.json", + "name": "libgrapplefrc", + "version": "2025.1.0", + "frcYear": "2025", + "uuid": "8ef3423d-9532-4665-8339-206dae1d7168", + "mavenUrls": [ + "https://storage.googleapis.com/grapple-frc-maven" + ], + "jsonUrl": "https://storage.googleapis.com/grapple-frc-maven/libgrapplefrc2025.json", + "javaDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcjava", + "version": "2025.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcdriver", + "version": "2025.1.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrccpp", + "version": "2025.1.0", + "libName": "grapplefrc", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcdriver", + "version": "2025.1.0", + "libName": "grapplefrcdriver", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json index a85f5c1..df5da73 100644 --- a/vendordeps/maple-sim.json +++ b/vendordeps/maple-sim.json @@ -1,7 +1,7 @@ { "fileName": "maple-sim.json", "name": "maplesim", - "version": "0.3.6", + "version": "0.3.9", "frcYear": "2025", "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.ironmaple", "artifactId": "maplesim-java", - "version": "0.3.6" + "version": "0.3.9" }, { "groupId": "org.dyn4j",