From: mixxlto Date: Wed, 21 Jan 2026 06:19:45 +0000 (-0800) Subject: changes X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=c7f69337278e3aaf705ae2fa68ee4f6c4eead2e9;p=FRC2026.git changes --- diff --git a/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java b/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java index 1a8b8e0..e770a5c 100644 --- a/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java +++ b/src/main/java/frc/robot/controls/PS5ControllerDriverConfig.java @@ -12,6 +12,7 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; +import edu.wpi.first.wpilibj2.command.WaitCommand; import frc.robot.Robot; import frc.robot.commands.gpm.TurretAutoShoot; import frc.robot.constants.Constants; @@ -66,10 +67,12 @@ public class PS5ControllerDriverConfig extends BaseDriverConfig { ()->false, getDrivetrain()).withTimeout(2)); driver.get(PS5Button.LB).onTrue( - new InstantCommand(() -> { - shooter.setFeeder(ShooterConstants.FEEDER_RUN_POWER); - shooter.setShooter(ShooterConstants.SHOOTER_VELOCITY); - })).onFalse( + new SequentialCommandGroup( + new InstantCommand(()-> shooter.setShooter(ShooterConstants.SHOOTER_VELOCITY)), + new WaitCommand(0.8), + new InstantCommand(()-> shooter.setFeeder(ShooterConstants.FEEDER_RUN_POWER)) + ) + ).onFalse( new InstantCommand(() -> { shooter.setFeeder(0); shooter.setShooter(0); diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index 1b5919e..5e9e2cf 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -9,21 +9,9 @@ import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; - -import au.grapplerobotics.ConfigurationFailedException; -import au.grapplerobotics.LaserCan; -import au.grapplerobotics.interfaces.LaserCanInterface.Measurement; -import au.grapplerobotics.interfaces.LaserCanInterface.RangingMode; -import au.grapplerobotics.interfaces.LaserCanInterface.RegionOfInterest; -import au.grapplerobotics.interfaces.LaserCanInterface.TimingBudget; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.Measure; -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.SequentialCommandGroup; -import edu.wpi.first.wpilibj2.command.WaitCommand; -import edu.wpi.first.wpilibj2.command.WaitUntilCommand; + import frc.robot.constants.Constants; import frc.robot.constants.IdConstants; @@ -44,7 +32,7 @@ public class Shooter { public Shooter(){ TalonFXConfiguration config = new TalonFXConfiguration(); - config.Slot0.kP = 0.1; //tune p value + config.Slot0.kP = 0.2; //tune p value config.Slot0.kI = 0; config.Slot0.kD = 0; config.Slot0.kV = 0.12; //Maximum rps = 100 --> 12V/100rps