From eb7d1edf359f0fdda1640fc4f46e0f905976e865 Mon Sep 17 00:00:00 2001 From: DylanTaylor29 <132412179+DylanTaylor29@users.noreply.github.com> Date: Thu, 12 Feb 2026 19:33:02 -0500 Subject: [PATCH 1/2] made everything but the turret a simulation --- src/main/java/frc/robot/Robot.java | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index f3846ab..2d061f3 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -33,7 +33,6 @@ import frc.robot.subsystems.drive.GyroIOBoron; import frc.robot.subsystems.drive.ModuleIO; import frc.robot.subsystems.drive.ModuleIOSimWPI; -import frc.robot.subsystems.drive.ModuleIOTalonFX; import frc.robot.subsystems.feeder.Feeder; import frc.robot.subsystems.feeder.KickerIO; import frc.robot.subsystems.feeder.KickerIOSimSpark; @@ -54,7 +53,6 @@ import frc.robot.subsystems.launcher.TurretIOSpark; import frc.robot.subsystems.vision.Vision; import frc.robot.subsystems.vision.VisionIO; -import frc.robot.subsystems.vision.VisionIOPhotonVision; import frc.robot.subsystems.vision.VisionIOPhotonVisionSim; import frc.robot.util.CanandgyroThread; import frc.robot.util.SparkOdometryThread; @@ -116,18 +114,22 @@ public Robot() { drive = new Drive( new GyroIOBoron(), - new ModuleIOTalonFX(DriveConstants.FrontLeft), - new ModuleIOTalonFX(DriveConstants.FrontRight), - new ModuleIOTalonFX(DriveConstants.BackLeft), - new ModuleIOTalonFX(DriveConstants.BackRight)); + new ModuleIOSimWPI(DriveConstants.FrontLeft), + new ModuleIOSimWPI(DriveConstants.FrontRight), + new ModuleIOSimWPI(DriveConstants.BackLeft), + new ModuleIOSimWPI(DriveConstants.BackRight)); vision = new Vision( drive::addVisionMeasurement, drive::getPose, - new VisionIOPhotonVision(cameraFrontRightName, robotToFrontRightCamera), - new VisionIOPhotonVision(cameraFrontLeftName, robotToFrontLeftCamera), - new VisionIOPhotonVision(cameraBackRightName, robotToBackRightCamera), - new VisionIOPhotonVision(cameraBackLeftName, robotToBackLeftCamera)); + new VisionIOPhotonVisionSim( + cameraFrontRightName, robotToFrontRightCamera, drive::getPose), + new VisionIOPhotonVisionSim( + cameraFrontLeftName, robotToFrontLeftCamera, drive::getPose), + new VisionIOPhotonVisionSim( + cameraBackRightName, robotToBackRightCamera, drive::getPose), + new VisionIOPhotonVisionSim( + cameraBackLeftName, robotToBackLeftCamera, drive::getPose)); launcher = new Launcher( drive::getPose, From 13143dd9f3fad6eff4f28e196e6ef71f47892dd5 Mon Sep 17 00:00:00 2001 From: nlaverdure Date: Thu, 12 Feb 2026 20:35:04 -0500 Subject: [PATCH 2/2] invert motor and update gear ratio --- .../frc/robot/subsystems/launcher/LauncherConstants.java | 6 +++--- .../java/frc/robot/subsystems/launcher/TurretIOSpark.java | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/launcher/LauncherConstants.java b/src/main/java/frc/robot/subsystems/launcher/LauncherConstants.java index 3afc659..499b3ff 100644 --- a/src/main/java/frc/robot/subsystems/launcher/LauncherConstants.java +++ b/src/main/java/frc/robot/subsystems/launcher/LauncherConstants.java @@ -71,15 +71,15 @@ public static final class TurretConstants { // Geometry public static final Transform3d chassisToTurretBase = new Transform3d(Inches.of(0), Inches.of(10), Inches.of(22), Rotation3d.kZero); - public static final Rotation2d absEncoderOffset = new Rotation2d(0.5); - public static final Rotation2d mechanismOffset = Rotation2d.kCCW_Pi_2; + public static final Rotation2d absEncoderOffset = new Rotation2d(5.3); + public static final Rotation2d mechanismOffset = Rotation2d.k180deg; public static final Angle rangeOfMotion = Degrees.of(240); // Position controller public static final double kPReal = 0.5; // Motor controller - public static final double motorReduction = 5.0; + public static final double motorReduction = 9.0 * 72.0 / 12.0; public static final AngularVelocity maxAngularVelocity = NEO550Constants.kFreeSpeed.div(motorReduction); public static final double encoderPositionFactor = (2 * Math.PI) / motorReduction; // Radians diff --git a/src/main/java/frc/robot/subsystems/launcher/TurretIOSpark.java b/src/main/java/frc/robot/subsystems/launcher/TurretIOSpark.java index 0272157..325c817 100644 --- a/src/main/java/frc/robot/subsystems/launcher/TurretIOSpark.java +++ b/src/main/java/frc/robot/subsystems/launcher/TurretIOSpark.java @@ -57,7 +57,7 @@ public TurretIOSpark() { var turnConfig = new SparkMaxConfig(); turnConfig - .inverted(false) + .inverted(true) .idleMode(IdleMode.kBrake) .smartCurrentLimit(NEO550Constants.kDefaultSupplyCurrentLimit) .voltageCompensation(RobotConstants.kNominalVoltage);