From 12df1bfc3d4a07bf5c637b3ba6e9d4200ab9b4bd Mon Sep 17 00:00:00 2001 From: rhit-halseysh <119546114+rhit-halseysh@users.noreply.github.com> Date: Thu, 29 Jan 2026 19:28:32 -0500 Subject: [PATCH] Fix instantiation of RotaryMechCharacteristics and update Hopper setGoal method to include angular parameters --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/subsystems/Vision/Vision.java | 2 ++ src/main/java/frc/robot/subsystems/hopper/Hopper.java | 4 ++-- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 8579bd1..2e4003d 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -123,7 +123,7 @@ public final class ShooterConstants { public static final Angle STARTING_ANGLE = Rotations.of(0.0); public static final Distance WHEEL_RADIUS = Meters.of(0.5); public static final RotaryMechCharacteristics CONSTANTS = - RotaryMechCharacteristics(OFFSET, WHEEL_RADIUS, MIN_ANGLE, MAX_ANGLE, STARTING_ANGLE); + new RotaryMechCharacteristics(OFFSET, WHEEL_RADIUS, MIN_ANGLE, MAX_ANGLE, STARTING_ANGLE); public static final double IDLE_SPEED_RPM = (1.0); public static final double HUB_SPEED_RPM = (1.0); public static final double TOWER_SPEED_RPM = (1.0); diff --git a/src/main/java/frc/robot/subsystems/Vision/Vision.java b/src/main/java/frc/robot/subsystems/Vision/Vision.java index a58551e..ba4b9dc 100644 --- a/src/main/java/frc/robot/subsystems/Vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/Vision/Vision.java @@ -1,3 +1,5 @@ +package frc.robot.subsystems.Vision; + import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; import frc.lib.W8.io.vision.VisionIO; diff --git a/src/main/java/frc/robot/subsystems/hopper/Hopper.java b/src/main/java/frc/robot/subsystems/hopper/Hopper.java index d1ac91f..e86d633 100644 --- a/src/main/java/frc/robot/subsystems/hopper/Hopper.java +++ b/src/main/java/frc/robot/subsystems/hopper/Hopper.java @@ -12,7 +12,7 @@ import static edu.wpi.first.units.Units.*; import edu.wpi.first.units.measure.*; -import frc.robot.Constants.HopperConstants; +import frc.robot.Constants.HopperConstants.*; public class Hopper extends SubsystemBase { private FlywheelMechanism _io; @@ -37,7 +37,7 @@ public Hopper(FlywheelMechanism io) { public void setGoal(double position) { Distance positionInches = Inches.of(position); - _io.runPosition(HopperConstants.CONVERTER.toAngle(positionInches), PIDSlot.SLOT_0); + _io.runPosition(HopperConstants.CONVERTER.toAngle(positionInches), HopperConstants.ANGULAR_VELOCITY, HopperConstants.ANGULAR_ACCELERATION, null, PIDSlot.SLOT_0); } @Override