80 lines
2.9 KiB
Java
Raw Normal View History

2025-02-06 19:08:24 -05:00
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands;
2025-02-12 18:40:27 -05:00
import static edu.wpi.first.units.Units.*;
2025-02-17 18:33:49 -05:00
import java.util.function.DoubleSupplier;
2025-02-12 18:40:27 -05:00
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
2025-02-06 19:08:24 -05:00
import edu.wpi.first.wpilibj2.command.Command;
2025-02-12 18:40:27 -05:00
import frc.robot.TunerConstants.TunerConstants;
2025-02-17 18:33:49 -05:00
import frc.robot.subsystems.CommandSwerveDrivetrain;
2025-02-06 19:08:24 -05:00
import frc.robot.subsystems.Limelight3;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class Forme3 extends Command {
private Limelight3 limelight3;
2025-02-12 18:40:27 -05:00
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
2025-02-17 18:33:49 -05:00
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
private CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
private DoubleSupplier x;
private DoubleSupplier y;
2025-02-12 18:40:27 -05:00
/* Setting up bindings for necessary control of the swerve drive platform */
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
2025-02-06 19:08:24 -05:00
/** Creates a new Forme3. */
2025-02-17 18:33:49 -05:00
public Forme3(Limelight3 limelight3,CommandSwerveDrivetrain drivetrain, DoubleSupplier x, DoubleSupplier y) {
2025-02-06 19:08:24 -05:00
this.limelight3 = limelight3;
2025-02-17 18:33:49 -05:00
this.drivetrain = drivetrain;
this.x = x;
this.y = y;
addRequirements(limelight3,drivetrain);
2025-02-06 19:08:24 -05:00
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
limelight3.Forme();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
2025-02-17 18:33:49 -05:00
double a = limelight3.getX();
2025-02-06 19:08:24 -05:00
if(limelight3.getV() == true){
2025-02-17 18:33:49 -05:00
drivetrain.setControl(drive.
withRotationalRate(a/10).
withVelocityX(x.getAsDouble()).
withVelocityY(y.getAsDouble()));
System.out.println(a/10);
2025-02-06 19:08:24 -05:00
}
else{
2025-02-17 18:33:49 -05:00
drivetrain.setControl(drive.
withRotationalRate(0).
withVelocityX(0).
withVelocityY(0));
2025-02-06 19:08:24 -05:00
}
}
// Called once the command ends or is interrupted.
@Override
2025-02-12 18:40:27 -05:00
public void end(boolean interrupted) {
2025-02-17 18:33:49 -05:00
drivetrain.setControl(drive.
withRotationalRate(0).
withVelocityX(0).
withVelocityY(0));
2025-02-12 18:40:27 -05:00
}
2025-02-06 19:08:24 -05:00
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}