mirror of
https://github.com/Team4388/2023WayOfTheRobot.git
synced 2026-06-09 08:38:02 -06:00
DRIVING WORKS FIELD RELATIVE NO PROBLEMS
This commit is contained in:
@@ -5,6 +5,7 @@
|
||||
package frc4388.robot.commands;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import frc4388.robot.subsystems.SwerveDrive;
|
||||
import frc4388.utility.RobotGyro;
|
||||
@@ -15,7 +16,7 @@ public class AutoBalance extends PelvicInflammatoryDisease {
|
||||
|
||||
/** Creates a new AutoBalanceTF2. */
|
||||
public AutoBalance(RobotGyro gyro, SwerveDrive drive) {
|
||||
super(1.0, 0, 0, 0);
|
||||
super(0.6, 0, 0, 0);
|
||||
|
||||
this.gyro = gyro;
|
||||
this.drive = drive;
|
||||
@@ -34,7 +35,7 @@ public class AutoBalance extends PelvicInflammatoryDisease {
|
||||
public void runWithOutput(double output) {
|
||||
double out2 = MathUtil.clamp(output / 40, -.5, .5);
|
||||
if (Math.abs(gyro.getPitch()) < 3) out2 = 0;
|
||||
drive.drive(out2, 0, 0, false);
|
||||
drive.driveWithInput(new Translation2d(0, out2), new Translation2d(), false);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -1,75 +0,0 @@
|
||||
// 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 frc4388.robot.commands;
|
||||
|
||||
import java.util.function.Supplier;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.filter.SlewRateLimiter;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.Constants.SwerveDriveConstants;
|
||||
import frc4388.robot.subsystems.SwerveDrive;
|
||||
|
||||
public class DriveWithInput extends CommandBase {
|
||||
|
||||
private final SwerveDrive swerve;
|
||||
|
||||
private final Supplier<Double> xSpeed;
|
||||
private final Supplier<Double> ySpeed;
|
||||
private final Supplier<Double> rot;
|
||||
private final boolean fieldRelative;
|
||||
|
||||
private final SlewRateLimiter xLimiter, yLimiter, rotLimiter;
|
||||
|
||||
/** Creates a new DriveWithInput. */
|
||||
public DriveWithInput(SwerveDrive swerve, Supplier<Double> xSpeed, Supplier<Double> ySpeed, Supplier<Double> rot, boolean fieldRelative) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.swerve = swerve;
|
||||
this.xSpeed = xSpeed;
|
||||
this.ySpeed = ySpeed;
|
||||
this.rot = rot;
|
||||
this.fieldRelative = fieldRelative;
|
||||
|
||||
this.xLimiter = new SlewRateLimiter(3);
|
||||
this.yLimiter = new SlewRateLimiter(3);
|
||||
this.rotLimiter = new SlewRateLimiter(3);
|
||||
|
||||
addRequirements(swerve);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double x = xSpeed.get();
|
||||
double y = ySpeed.get();
|
||||
double r = rot.get();
|
||||
|
||||
x = -xLimiter.calculate(MathUtil.applyDeadband(x * -0.3, 0.02) * Units.feetToMeters(SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND));
|
||||
y = -yLimiter.calculate(MathUtil.applyDeadband(y * 0.3, 0.02) * Units.feetToMeters(SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND));
|
||||
r = -rotLimiter.calculate(MathUtil.applyDeadband(r * 0.3, 0.02) * Units.feetToMeters(5*Math.PI));
|
||||
|
||||
swerve.drive(x, y, r, fieldRelative);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
System.out.println("----------------------------------------------------------------");
|
||||
System.out.println("DriveWithInput ended");
|
||||
System.out.println("Interrupted: " + interrupted);
|
||||
System.out.println("----------------------------------------------------------------");
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user