fixes to flywheel in order to operate more globally

This commit is contained in:
2026-06-03 10:03:34 -05:00
parent c8e9be1c08
commit 47c505742a
3 changed files with 36 additions and 33 deletions

View File

@@ -17,16 +17,15 @@ import org.firstinspires.ftc.teamcode.utilsv2.Shooter;
public class NewShooterTest extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Shooter shooter;
Flywheel rpmFlywheel;
public static boolean intake = true;
public static boolean shoot = false;
public static double intakePower = 1.0;
public static double transferShootPower = -1;
public static double transferIntakePower = -1.0;
public static double transferIntakePower = -1;
public static double turretPos = 0.51;
public static double hoodPos = 0.51;
public static double flywheel = 0;
@@ -45,16 +44,15 @@ public class NewShooterTest extends LinearOpMode {
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
Shooter shooter = new Shooter(
shooter = new Shooter(
robot,
new MultipleTelemetry(
telemetry,
FtcDashboard.getInstance().getTelemetry()
),
TELE,
Constants.createFollower(hardwareMap),
true
);
@@ -130,7 +128,10 @@ public class NewShooterTest extends LinearOpMode {
}
}
TELE.addData("Flywheel Velocity", (robot.shooter1.getVelocity() * 60) / 28);
TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28);
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28);
TELE.addData("Flywheel Averag Velocity", rpmFlywheel.getAverageVelocity());
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF);
TELE.update();
shooter.update();

View File

@@ -5,12 +5,19 @@ import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import java.util.LinkedList;
public class Flywheel {
Robot robot;
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
// public PIDFCoefficients shooterPIDF1, shooterPIDF2;
public static PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
private double velo = 0.0;
private double velo1 = 0.0;
@@ -26,7 +33,7 @@ public class Flywheel {
public Flywheel(Robot rob) {
robot = rob;
shooterPIDF1 = new PIDFCoefficients(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / 12);
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
}
public double getVelo() {
@@ -50,25 +57,26 @@ public class Flywheel {
}
// Set the robot PIDF for the next cycle.
private double prevF = 0;
public static double voltagePIDFDifference = 0.8;
public void setPIDF(double p, double i, double d, double f) {
shooterPIDF1.p = p;
shooterPIDF1.i = i;
shooterPIDF1.d = d;
shooterPIDF1.f = f;
shooterPIDF.p = p;
shooterPIDF.i = i;
shooterPIDF.d = d;
shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
}
// if (Math.abs(prevF - f) > voltagePIDFDifference) {
//
// robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
//
// prevF = f;
// }
private double prevF = 0;
public static double voltagePIDFDifference = 0.8;
public void setF(double f){
if (Math.abs(prevF - f) > voltagePIDFDifference) {
shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f;
}
}
// Convert from RPM to Ticks per Second

View File

@@ -48,11 +48,6 @@ public class Robot {
public DcMotorEx backRight;
public DcMotorEx intake;
public DcMotorEx transfer;
public PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
// public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public DcMotorEx shooter1;
public DcMotorEx shooter2;
@@ -108,10 +103,9 @@ public class Robot {
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
// shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter1.setVelocity(0);
// shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
hood = hardwareMap.get(Servo.class, "hood");