]> git.taranathan.com Git - FRC2026.git/commitdiff
a
authormaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Sat, 14 Feb 2026 21:48:37 +0000 (13:48 -0800)
committermaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Sat, 14 Feb 2026 21:48:37 +0000 (13:48 -0800)
src/main/java/frc/robot/RobotContainer.java
src/main/java/frc/robot/commands/gpm/AutoShootCommand.java
src/main/java/frc/robot/subsystems/shooter/Shooter.java
src/main/java/frc/robot/subsystems/turret/Turret.java

index 6dbc0656700f78d991480e6db38c5e1f278459fd..10600ef4eacea15fdc7c1531033225de5290caf3 100644 (file)
@@ -86,7 +86,7 @@ public class RobotContainer {
 
       case WaffleHouse: // AKA Betabot
         turret = new Turret();
-        //shooter = new Shooter();
+        shooter = new Shooter();
         //hood = new Hood();
 
       case SwerveCompetition: // AKA "Vantage"
index 89507cd9426435f46310c2c1c64da1341c69a070..4f1ce7cf2bff8b794472a32e7b87e80f877f9cd9 100644 (file)
@@ -181,7 +181,7 @@ public class AutoShootCommand extends Command {
         lastHoodAngle = hoodAngle;
 
         if (Math.abs(lastTurretAngle.getDegrees() - turretSetpoint) > 90) {
-            velocityAdjustment = -drivetrain.getAngularRate(2) * 1.4;
+            velocityAdjustment = -drivetrain.getAngularRate(2) * 1.0;
         }
     }
 
@@ -207,7 +207,7 @@ public class AutoShootCommand extends Command {
 
         turret.setFieldRelativeTarget(new Rotation2d(Units.degreesToRadians(turretSetpoint)), turretVelocity - drivetrain.getAngularRate(2));
         //hood.setFieldRelativeTarget(new Rotation2d(Units.degreesToRadians(hoodSetpoint)), hoodVelocity);
-        //shooter.setShooter(goalState.exitVel());
+        shooter.setShooter(goalState.exitVel());
 
         SmartDashboard.putNumber("Turret Calculated Setpoint", turretSetpoint);
         SmartDashboard.putNumber("Hood Calculate Setpoint", hoodSetpoint);
@@ -224,7 +224,7 @@ public class AutoShootCommand extends Command {
     public void end(boolean interrupted) {
         // Set the turret to a safe position when the command ends
         turret.setFieldRelativeTarget(new Rotation2d(0.0), 0.0);
-        //shooter.setShooter(0.0);
+        shooter.setShooter(0.0);
         //hood.setFieldRelativeTarget(new Rotation2d(Units.degreesToRadians(HoodConstants.MAX_ANGLE)), 0.0);
         if(spindexer != null){
             spindexer.stopSpindexer();
index af372ff15274bcba8c5916fa44225cd0f5091516..e5709bbaf8138f1ff3eed139e5af3781ec042c24 100644 (file)
@@ -1,4 +1,4 @@
-package frc.robot.subsystems.Shooter;
+package frc.robot.subsystems.shooter;
 
 import org.littletonrobotics.junction.AutoLogOutput;
 import org.littletonrobotics.junction.Logger;
@@ -19,6 +19,7 @@ import au.grapplerobotics.interfaces.LaserCanInterface.TimingBudget;
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
 import frc.robot.constants.Constants;
 import frc.robot.constants.IdConstants;
@@ -62,16 +63,20 @@ public class Shooter extends SubsystemBase implements ShooterIO {
         shooterMotorRight.getConfigurator().apply(
             new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Coast)
         );
+
+        SmartDashboard.putData("Turn on shooter", new InstantCommand(()-> setShooter(20.0)));
     }
 
     @Override
     public void periodic(){
+        shooterMotorRight.set(1.0);
+        shooterMotorLeft.set(1.0);
         updateInputs();
 
         powerModifier = SmartDashboard.getNumber("shooter power modifier", powerModifier);
         SmartDashboard.putNumber("shooter power modifier", powerModifier);
-        shooterMotorLeft.setControl(voltageRequest.withVelocity(shooterTargetSpeed * powerModifier));
-        shooterMotorRight.setControl(voltageRequest.withVelocity(shooterTargetSpeed * powerModifier));          
+        //shooterMotorLeft.setControl(voltageRequest.withVelocity(shooterTargetSpeed * powerModifier));
+        //shooterMotorRight.setControl(voltageRequest.withVelocity(shooterTargetSpeed * powerModifier));          
     }
 
     public void deactivateShooterAndFeeder() {
index d0b0ebc66bf5f3d9b74b63535ba9df09fdc78896..2a7721dbd1a520cde2a03ab93bd4e02015509166 100644 (file)
@@ -162,6 +162,8 @@ public class Turret extends SubsystemBase implements TurretIO{
                double motorRotations = turretRotations * TurretConstants.TURRET_GEAR_RATIO;
                motor.setPosition(motorRotations);
 
+               motor.setPosition(0.0); //TODO: remove after hardcrt works
+
                SmartDashboard.putData("Turret Mech", mech);
 
                SmartDashboard.putData("Turret to 90", new InstantCommand(()-> setFieldRelativeTarget(new Rotation2d(Math.PI/2), 0.0)));
@@ -244,19 +246,11 @@ public class Turret extends SubsystemBase implements TurretIO{
 
         Logger.recordOutput("Turret/Voltage", motor.getMotorVoltage().getValue());
                Logger.recordOutput("Turret/velocitySetpoint", targetVelocity / GEAR_RATIO);
+               Logger.recordOutput("Turret/setpointDeg", Units.radiansToDegrees(setpoint.position));
 
                // --- Visualization ---
                ligament.setAngle(Units.radiansToDegrees(getPositionRad()));
 
-               SmartDashboard.putNumber("Turret SetpointDeg",
-                               Units.radiansToDegrees(setpoint.position));
-               SmartDashboard.putNumber("Turret motorVelRotPerSec",
-                               Units.radiansToDegrees(motorVelRotPerSec));
-        SmartDashboard.putNumber("Turret targetVelocity",
-                               Units.radiansToDegrees(targetVelocity));
-               SmartDashboard.putNumber("Turret Position Deg",
-                               Units.rotationsToDegrees(motor.getPosition().getValueAsDouble()) / GEAR_RATIO);
-
                updateInputs();
                Logger.processInputs("Turret", inputs);