speed in auto

check fo rspeed in auto
This commit is contained in:
SHikhar
2026-02-27 20:02:12 -07:00
parent e299d3bd0a
commit 3b5ff2a252
3 changed files with 30 additions and 22 deletions
+14 -15
View File
@@ -26,6 +26,7 @@ import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand; import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton; import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger; import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc4388.robot.commands.alignment.AutoAlign; import frc4388.robot.commands.alignment.AutoAlign;
@@ -95,7 +96,7 @@ public class RobotContainer {
private Command autoCommand; private Command autoCommand;
private Command RobotIntakeDown = new SequentialCommandGroup( private Command RobotIntakeExtended = new SequentialCommandGroup(
new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Extended), m_robotIntake) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Extended), m_robotIntake)
); );
@@ -118,25 +119,24 @@ public class RobotContainer {
// // .andThen(new InstantCommand(() -> m_robotSwerveDrive.softStop(), m_robotSwerveDrive)) // // .andThen(new InstantCommand(() -> m_robotSwerveDrive.softStop(), m_robotSwerveDrive))
// ); // );
private Command RobotReadyToShoot = new SequentialCommandGroup( private Command RobotRev = new SequentialCommandGroup(
new InstantCommand(()-> m_robotIntake.setMode(IntakeMode.Idle), m_robotIntake), new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter),
new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Extended), m_robotIntake),
new InstantCommand(() -> m_robotIntake.rollerStop(), m_robotIntake)
); );
private Command IntakeRetracted = new SequentialCommandGroup( private Command RobotIntakeRetracted = new SequentialCommandGroup(
new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Retracted), m_robotIntake) new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Retracted), m_robotIntake)
); );
private Command RobotShoot = new SequentialCommandGroup( private Command RobotShoot = new SequentialCommandGroup(
// TEST NEW AUTO ALIGN // TEST NEW AUTO ALIGN
//new AutoAlign(m_robotSwerveDrive, m_vision, new Pose2d(FieldPositions.HUB_POSITION, new Rotation2d(0)), false), //new AutoAlign(m_robotSwerveDrive, m_vision, new Pose2d(FieldPositions.HUB_POSITION, new Rotation2d(0)), false),
new InstantCommand(()-> m_robotShooter.spinUpShooting(), m_robotShooter), new WaitUntilCommand(m_robotShooter::isShooterUpToSpeed),
new InstantCommand(()-> m_robotShooter.allowShooting(), m_robotShooter), new InstantCommand(()-> m_robotShooter.allowShooting(), m_robotShooter),
new WaitCommand(2), new WaitCommand(5),
IntakeRetracted, new InstantCommand(() -> m_robotShooter.denyShooting(), m_robotShooter),
new WaitCommand(3), new InstantCommand(()->m_robotShooter.spinUpIdle(), m_robotShooter)
new InstantCommand(()->m_robotShooter.spinUpIdle(), m_robotShooter),
new InstantCommand(() -> m_robotShooter.denyShooting(), m_robotShooter)
); );
@@ -158,12 +158,11 @@ public class RobotContainer {
m_robotShooter.io.updateGains(); m_robotShooter.io.updateGains();
}, true); }, true);
NamedCommands.registerCommand("Robot Rev Up", RobotReadyToShoot); NamedCommands.registerCommand("Robot Rev Up", RobotRev);
NamedCommands.registerCommand("Intake Retracted", IntakeRetracted); NamedCommands.registerCommand("Robot Intake Retracted", RobotIntakeRetracted);
NamedCommands.registerCommand("Robot Shoot", RobotShoot); NamedCommands.registerCommand("Robot Shoot", RobotShoot);
// NamedCommands.registerCommand("Lidar Intake", LidarIntake); // NamedCommands.registerCommand("Lidar Intake", LidarIntake);
NamedCommands.registerCommand("Robot Intake Down", RobotIntakeDown); NamedCommands.registerCommand("Robot Intake Extended", RobotIntakeExtended);
DriverStation.silenceJoystickConnectionWarning(true); DriverStation.silenceJoystickConnectionWarning(true);
@@ -5,14 +5,14 @@ package frc4388.robot.constants;
*/ */
public final class BuildConstants { public final class BuildConstants {
public static final String MAVEN_GROUP = ""; public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2026KPopRobotHunters-new"; public static final String MAVEN_NAME = "2026KPopRobotHunters";
public static final String VERSION = "unspecified"; public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 85; public static final int GIT_REVISION = 112;
public static final String GIT_SHA = "3d22607e5a8805f6bafa42d0e8ae41a719741842"; public static final String GIT_SHA = "e299d3bd0a4dda5addf954455b0628b150cf6d35";
public static final String GIT_DATE = "2026-02-25 16:33:01 MST"; public static final String GIT_DATE = "2026-02-27 18:44:44 MST";
public static final String GIT_BRANCH = "shikhar-op-controls"; public static final String GIT_BRANCH = "shikhar-op-controls";
public static final String BUILD_DATE = "2026-02-25 17:33:10 MST"; public static final String BUILD_DATE = "2026-02-27 20:01:01 MST";
public static final long BUILD_UNIX_TIME = 1772065990668L; public static final long BUILD_UNIX_TIME = 1772247661187L;
public static final int DIRTY = 1; public static final int DIRTY = 1;
private BuildConstants(){} private BuildConstants(){}
@@ -29,6 +29,7 @@ public class Shooter extends SubsystemBase {
// Supplier<Pose2d> m_swervePoseSupplier; // Supplier<Pose2d> m_swervePoseSupplier;
public boolean badShooterVelocity;
public Shooter( public Shooter(
@@ -75,6 +76,7 @@ public class Shooter extends SubsystemBase {
} }
public void allowShooting() { public void allowShooting() {
shooterButtonReady = true; shooterButtonReady = true;
} }
@@ -89,6 +91,12 @@ public class Shooter extends SubsystemBase {
return mode; return mode;
} }
@AutoLogOutput
public boolean isShooterUpToSpeed() {
return !badShooterVelocity;
}
@Override @Override
public void periodic() { public void periodic() {
@@ -132,7 +140,8 @@ public class Shooter extends SubsystemBase {
double shooterSpeed = Math.abs(state.motor1Velocity.in(RotationsPerSecond) + state.motor2Velocity.in(RotationsPerSecond)) / 2; double shooterSpeed = Math.abs(state.motor1Velocity.in(RotationsPerSecond) + state.motor2Velocity.in(RotationsPerSecond)) / 2;
double shooterSpeedTarget = Math.abs(state.motor1TargetVelocity.in(RotationsPerSecond) + state.motor2TargetVelocity.in(RotationsPerSecond)) / 2; double shooterSpeedTarget = Math.abs(state.motor1TargetVelocity.in(RotationsPerSecond) + state.motor2TargetVelocity.in(RotationsPerSecond)) / 2;
boolean badShooterVelocity = Math.abs(shooterSpeed - shooterSpeedTarget) > ShooterConstants.SHOOTER_SPEED_TOLERANCE.get(); badShooterVelocity = Math.abs(shooterSpeed - shooterSpeedTarget) > ShooterConstants.SHOOTER_SPEED_TOLERANCE.get();
switch (mode) { switch (mode) {
case Shooting: case Shooting: