15 Commits

Author SHA1 Message Date
adbe9ad023 limelight works 2026-01-09 22:49:24 -06:00
37c74fc85f limelight test updated 2026-01-09 22:20:22 -06:00
0c9e8c3287 flywheel test complete - need to tune maxStep and kp once on robot 2026-01-08 21:06:36 -06:00
506e45ac19 stash 2026-01-08 20:28:55 -06:00
8b07ed5579 stash 2026-01-06 19:52:26 -06:00
c368552724 stash 2026-01-05 17:29:03 -06:00
934cabafc5 stash 2026-01-05 17:28:36 -06:00
05107ab828 stash 2026-01-05 14:14:26 -06:00
7ef9d3a556 to test new shooter 2026-01-03 16:30:55 -06:00
a84891bc06 to test new shooter 2026-01-03 16:07:14 -06:00
21b4b0b4f5 stash 2026-01-03 16:02:42 -06:00
5faa373cad stash 2026-01-03 16:01:11 -06:00
32d481c031 stash 2026-01-03 15:58:25 -06:00
3e8e2c2b4b fixed ll class 2025-10-13 18:12:03 -05:00
458b6f53a2 even more updates 2025-10-11 22:03:40 -05:00
14 changed files with 329 additions and 58 deletions

View File

@@ -1,4 +0,0 @@
package org.firstinspires.ftc.teamcode.constants;
public class blank {
}

View File

@@ -1,5 +1,6 @@
package org.firstinspires.ftc.teamcode.libs.RR; package org.firstinspires.ftc.teamcode.libs.RR;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.canvas.Canvas;
@@ -211,6 +212,7 @@ public final class MecanumDrive {
headingDelta headingDelta
)); ));
return twist.velocity().value(); return twist.velocity().value();
} }
} }
@@ -222,7 +224,7 @@ public final class MecanumDrive {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
} }
// TODO: make sure your config has motors with these names (or change them) // TODO: make sure your HardwareConfig has motors with these names (or change them)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront"); leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack"); leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
@@ -237,7 +239,7 @@ public final class MecanumDrive {
// TODO: reverse motor directions if needed // TODO: reverse motor directions if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE); // leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI) // TODO: make sure your HardwareConfig has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot( lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection)); PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));

View File

@@ -28,7 +28,7 @@ public class OTOSLocalizer implements Localizer {
private Pose2d currentPose; private Pose2d currentPose;
public OTOSLocalizer(HardwareMap hardwareMap, Pose2d initialPose) { public OTOSLocalizer(HardwareMap hardwareMap, Pose2d initialPose) {
// TODO: make sure your config has an OTOS device with this name // TODO: make sure your HardwareConfig has an OTOS device with this name
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
otos = hardwareMap.get(SparkFunOTOS.class, "sensor_otos"); otos = hardwareMap.get(SparkFunOTOS.class, "sensor_otos");
currentPose = initialPose; currentPose = initialPose;

View File

@@ -29,7 +29,7 @@ public final class PinpointLocalizer implements Localizer {
private Pose2d txPinpointRobot = new Pose2d(0, 0, 0); private Pose2d txPinpointRobot = new Pose2d(0, 0, 0);
public PinpointLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) { public PinpointLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) {
// TODO: make sure your config has a Pinpoint device with this name // TODO: make sure your HardwareConfig has a Pinpoint device with this name
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
driver = hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint"); driver = hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint");

View File

@@ -232,7 +232,7 @@ public final class TankDrive {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
} }
// TODO: make sure your config has motors with these names (or change them) // TODO: make sure your HardwareConfig has motors with these names (or change them)
// add additional motors on each side if you have them // add additional motors on each side if you have them
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "left")); leftMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "left"));
@@ -248,7 +248,7 @@ public final class TankDrive {
// TODO: reverse motor directions if needed // TODO: reverse motor directions if needed
// leftMotors.get(0).setDirection(DcMotorSimple.Direction.REVERSE); // leftMotors.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI) // TODO: make sure your HardwareConfig has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot( lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection)); PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));

View File

@@ -37,7 +37,7 @@ public final class ThreeDeadWheelLocalizer implements Localizer {
private Pose2d pose; private Pose2d pose;
public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) { public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick, Pose2d initialPose) {
// TODO: make sure your config has **motors** with these names (or change them) // TODO: make sure your HardwareConfig has **motors** with these names (or change them)
// the encoders should be plugged into the slot matching the named motor // the encoders should be plugged into the slot matching the named motor
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par0"))); par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par0")));

View File

@@ -46,7 +46,7 @@ public final class TwoDeadWheelLocalizer implements Localizer {
private Pose2d pose; private Pose2d pose;
public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick, Pose2d initialPose) { public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick, Pose2d initialPose) {
// TODO: make sure your config has **motors** with these names (or change them) // TODO: make sure your HardwareConfig has **motors** with these names (or change them)
// the encoders should be plugged into the slot matching the named motor // the encoders should be plugged into the slot matching the named motor
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par"))); par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par")));

View File

@@ -3,55 +3,75 @@ package org.firstinspires.ftc.teamcode.tests;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.Robot; import java.util.List;
import org.firstinspires.ftc.teamcode.utils.subsystems.Limelight;
//TODO: fix to get the apriltag that it is reading
@Autonomous
@Config @Config
@TeleOp
public class LimelightTest extends LinearOpMode { public class LimelightTest extends LinearOpMode {
public static String MODE = "AT";
public static int pipe = 1;
MultipleTelemetry TELE; MultipleTelemetry TELE;
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
Robot robot; public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "Limelight");
robot = new Robot(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
limelight.pipelineSwitch(pipeline);
Limelight limelight = new Limelight(robot, TELE);
limelight.setMode(MODE);
limelight.setTelemetryOn(true);
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
limelight.start();
while (opModeIsActive()){ while (opModeIsActive()){
if (mode == 0){
limelight.setPipeline(pipe); limelight.pipelineSwitch(pipeline);
LLResult result = limelight.getLatestResult();
limelight.setMode(MODE); if (result != null) {
if (result.isValid()) {
limelight.update(); TELE.addData("tx", result.getTx());
TELE.addData("ty", result.getTy());
TELE.update();
}
}
} else if (mode == 1){
limelight.pipelineSwitch(1);
LLResult result = limelight.getLatestResult();
if (result != null && result.isValid()) {
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
for (LLResultTypes.FiducialResult fiducial : fiducials) {
int id = fiducial.getFiducialId();
TELE.addData("ID", id);
TELE.update(); TELE.update();
} }
} }
} else if (mode == 2){
limelight.pipelineSwitch(2);
LLResult result = limelight.getLatestResult();
if (result != null) {
if (result.isValid()) {
TELE.addData("tx", result.getTx());
TELE.addData("ty", result.getTy());
TELE.update();
}
}
} else if (mode == 3){
limelight.pipelineSwitch(3);
LLResult result = limelight.getLatestResult();
if (result != null) {
if (result.isValid()) {
TELE.addData("tx", result.getTx());
TELE.addData("ty", result.getTy());
TELE.update();
}
}
} else {
limelight.pipelineSwitch(0);
}
}
}
} }

View File

@@ -0,0 +1,68 @@
package org.firstinspires.ftc.teamcode.tests;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import org.firstinspires.ftc.teamcode.utils.Flywheel;
import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class ShooterTest extends LinearOpMode {
public static int mode = 0;
public static double parameter = 0.0;
// --- CONSTANTS YOU TUNE ---
public static double hoodPos = 0.501;
Robot robot;
Flywheel flywheel;
@Override
public void runOpMode() throws InterruptedException {
robot = new Robot(hardwareMap);
DcMotorEx leftShooter = robot.shooter1;
DcMotorEx rightShooter = robot.shooter2;
flywheel = new Flywheel();
MultipleTelemetry TELE = new MultipleTelemetry(
telemetry, FtcDashboard.getInstance().getTelemetry()
);
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
if (mode == 0) {
rightShooter.setPower(parameter);
leftShooter.setPower(parameter);
} else if (mode == 1) {
double powPID = flywheel.manageFlywheel((int) parameter, leftShooter.getCurrentPosition(), rightShooter.getCurrentPosition());
rightShooter.setPower(powPID);
leftShooter.setPower(powPID);
TELE.addData("PIDPower", powPID);
}
if (hoodPos != 0.501) {
robot.hood.setPosition(hoodPos);
}
TELE.addData("Used Velocity", flywheel.getVelo(leftShooter.getCurrentPosition(), rightShooter.getCurrentPosition()));
TELE.addData("Velocity1", flywheel.getVelo1());
TELE.addData("Velocity2", flywheel.getVelo2());
TELE.addData("Power", robot.shooter1.getPower());
TELE.addData("Steady?", flywheel.getSteady());
TELE.addData("Position1", robot.shooter1.getCurrentPosition()/28);
TELE.addData("Position2", robot.shooter2.getCurrentPosition()/28);
TELE.update();
}
}
}

View File

@@ -0,0 +1,104 @@
package org.firstinspires.ftc.teamcode.utils;
import com.acmerobotics.dashboard.config.Config;
@Config
public class Flywheel {
public static double kP = 0.001; // small proportional gain (tune this)
public static double maxStep = 0.06; // prevents sudden jumps
double initPos1 = 0.0;
double initPos2 = 0.0;
double stamp = 0.0;
double stamp1 = 0.0;
double ticker = 0.0;
double currentPos1 = 0.0;
double currentPos2 = 0.0;
double velo = 0.0;
double velo1 = 0.0;
double velo1a = 0.0;
double velo1b = 0.0;
double velo2 = 0.0;
double velo3 = 0.0;
double velo4 = 0.0;
double velo5 = 0.0;
double targetVelocity = 0.0;
double powPID = 0.0;
boolean steady = false;
public Flywheel() {
//robot = new Robot(hardwareMap);
}
public double getVelo(double shooter1CurPos, double shooter2CurPos) {
ticker++;
if (ticker % 2 == 0) {
velo5 = velo4;
velo4 = velo3;
velo3 = velo2;
velo2 = velo1;
currentPos1 = shooter1CurPos / 28;
currentPos2 = shooter2CurPos / 28;
stamp = getTimeSeconds(); //getRuntime();
velo1a = 60 * ((currentPos1 - initPos1) / (stamp - stamp1));
velo1b = 60 * ((currentPos2 - initPos2) / (stamp - stamp1));
initPos1 = currentPos1;
initPos2 = currentPos2;
stamp1 = stamp;
if (velo1a < 200){
velo1 = velo1b;
} else if (velo1b < 200){
velo1 = velo1a;
} else {
velo1 = (velo1a + velo1b) / 2;
}
}
return ((velo1 + velo2 + velo3 + velo4 + velo5) / 5);
}
public double getVelo1() { return (velo1a + velo2 + velo3 + velo4 + velo5) / 5; }
public double getVelo2() { return (velo1b + velo2 + velo3 + velo4 + velo5) / 5; }
public boolean getSteady() {
return steady;
}
private double getTimeSeconds() {
return (double) System.currentTimeMillis() / 1000.0;
}
public double manageFlywheel(int commandedVelocity, double shooter1CurPos, double shooter2CurPos) {
targetVelocity = commandedVelocity;
velo = getVelo(shooter1CurPos, shooter2CurPos);
// Flywheel PID code here
if (targetVelocity - velo > 500) {
powPID = 1.0;
} else if (velo - targetVelocity > 500) {
powPID = 0.0;
} else {
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
// --- PROPORTIONAL CORRECTION ---
double error = targetVelocity - velo;
double correction = kP * error;
// limit how fast power changes (prevents oscillation)
correction = Math.max(-maxStep, Math.min(maxStep, correction));
// --- FINAL MOTOR POWER ---
powPID = feed + correction;
// clamp to allowed range
powPID = Math.max(0, Math.min(1, powPID));
}
steady = (Math.abs(targetVelocity - velo) < 100.0);
return powPID;
}
public void update() {
}
}

View File

@@ -1,7 +1,15 @@
package org.firstinspires.ftc.teamcode.utils; package org.firstinspires.ftc.teamcode.utils;
import static org.firstinspires.ftc.teamcode.variables.HardwareConfig.*;
import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.IMU;
import com.qualcomm.robotcore.hardware.Servo;
public class Robot { public class Robot {
@@ -9,11 +17,43 @@ public class Robot {
public Limelight3A limelight3A; public Limelight3A limelight3A;
public IMU imu;
public DcMotorEx shooter1;
public DcMotorEx shooter2;
public Servo hood;
public Robot (HardwareMap hardwareMap) { public Robot (HardwareMap hardwareMap) {
//Define components w/ hardware map //Define components w/ hardware map
limelight3A = hardwareMap.get(Limelight3A.class, "limelight"); limelight3A = hardwareMap.get(Limelight3A.class, "limelight");
shooter1 = hardwareMap.get(DcMotorEx.class, "s1");
shooter2 = hardwareMap.get(DcMotorEx.class, "s2");
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
shooter2.setDirection(DcMotorSimple.Direction.REVERSE);
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
hood = hardwareMap.get(Servo.class, "hood");
if (USING_LL) {
limelight3A = hardwareMap.get(Limelight3A.class, "limelight");
limelight3A.start(); // This tells Limelight to start looking!
}
imu = hardwareMap.get(IMU.class, "imu");
RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP;
RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
RevHubOrientationOnRobot orientationOnRobot = new RevHubOrientationOnRobot(logoFacingDirection, usbFacingDirection);
imu.initialize(new IMU.Parameters(orientationOnRobot));
} }
} }

View File

@@ -1,4 +0,0 @@
package org.firstinspires.ftc.teamcode.utils.functions;
public class DistanceToTarget {
}

View File

@@ -6,11 +6,13 @@ import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.hardware.limelightvision.LLStatus; import com.qualcomm.hardware.limelightvision.LLStatus;
import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.robotcore.hardware.IMU;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D; import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
import org.firstinspires.ftc.robotcore.external.navigation.Position; import org.firstinspires.ftc.robotcore.external.navigation.Position;
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
import org.firstinspires.ftc.teamcode.variables.HardwareConfig;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Subsystem; import org.firstinspires.ftc.teamcode.utils.Subsystem;
@@ -42,17 +44,28 @@ public class Limelight implements Subsystem {
private double ty = 0.0; private double ty = 0.0;
private double tync = 0.0; private double tync = 0.0;
private double ta = 0.0;
private List<LLResultTypes.BarcodeResult> barcodeResults = new ArrayList<>(); private List<LLResultTypes.BarcodeResult> barcodeResults = new ArrayList<>();
private List<LLResultTypes.ClassifierResult> classifierResults = new ArrayList<>(); private List<LLResultTypes.ClassifierResult> classifierResults = new ArrayList<>();
private List<LLResultTypes.DetectorResult> detectorResults = new ArrayList<>(); private List<LLResultTypes.DetectorResult> detectorResults = new ArrayList<>();
private List<LLResultTypes.FiducialResult> fiducialResults = new ArrayList<>(); private List<LLResultTypes.FiducialResult> fiducialResults = new ArrayList<>();
private List<LLResultTypes.ColorResult> colorResults = new ArrayList<>(); private List<LLResultTypes.ColorResult> colorResults = new ArrayList<>();
private IMU imu;
public Limelight(Robot robot, MultipleTelemetry tele) { public Limelight(Robot robot, MultipleTelemetry tele) {
HardwareConfig.USING_LL= true;
this.limelight = robot.limelight3A; this.limelight = robot.limelight3A;
this.telemetry = tele; this.telemetry = tele;
limelight.pipelineSwitch(1); limelight.pipelineSwitch(1);
this.imu = robot.imu;
this.imu.resetYaw();
} }
@@ -62,12 +75,19 @@ public class Limelight implements Subsystem {
public void setMode(String newMode) { this.mode = newMode; } public void setMode(String newMode) { this.mode = newMode; }
/** ✅ MAIN UPDATE LOOP */ /** ✅ MAIN UPDATE LOOP */
@Override @Override
public void update() { public void update() {
result = limelight.getLatestResult(); result = limelight.getLatestResult();
status = limelight.getStatus(); status = limelight.getStatus();
if (result != null && (Objects.equals(status.getPipelineType(), "pipe_python") || result.isValid())){ if (result != null && (Objects.equals(status.getPipelineType(), "pipe_python") || result.isValid())){
// Refresh all cached values // Refresh all cached values
botpose = result.getBotpose(); botpose = result.getBotpose();
@@ -79,6 +99,7 @@ public class Limelight implements Subsystem {
txnc = result.getTxNC(); txnc = result.getTxNC();
ty = result.getTy(); ty = result.getTy();
tync = result.getTyNC(); tync = result.getTyNC();
ta = result.getTa();
barcodeResults = result.getBarcodeResults(); barcodeResults = result.getBarcodeResults();
classifierResults = result.getClassifierResults(); classifierResults = result.getClassifierResults();
detectorResults = result.getDetectorResults(); detectorResults = result.getDetectorResults();
@@ -105,6 +126,7 @@ public class Limelight implements Subsystem {
if (result != null && result.isValid()) { if (result != null && result.isValid()) {
telemetry.addData("LL Latency", getTotalLatency()); telemetry.addData("LL Latency", getTotalLatency());
telemetry.addData("Capture Latency", getCaptureLatency()); telemetry.addData("Capture Latency", getCaptureLatency());
@@ -115,7 +137,17 @@ public class Limelight implements Subsystem {
telemetry.addData("txnc", getTxNC()); telemetry.addData("txnc", getTxNC());
telemetry.addData("ty", getTy()); telemetry.addData("ty", getTy());
telemetry.addData("tync", getTyNC()); telemetry.addData("tync", getTyNC());
telemetry.addData("Botpose", getBotPose().toString()); telemetry.addData("ta", getTa());
telemetry.addData("BotX", getBotX());
telemetry.addData("BotY", getBotY());
if (Objects.equals(mode, "BR")) if (Objects.equals(mode, "BR"))
@@ -170,6 +202,15 @@ public class Limelight implements Subsystem {
public double getTy() { return ty; } public double getTy() { return ty; }
public double getTyNC() { return tync;} public double getTyNC() { return tync;}
public double getTa() {return ta;}
public double getBotX() {return getBotPose().getPosition().x;}
public double getBotY() {return getBotPose().getPosition().y;}
public List<LLResultTypes.BarcodeResult> getBarcodeResults() { return barcodeResults; } public List<LLResultTypes.BarcodeResult> getBarcodeResults() { return barcodeResults; }
public List<LLResultTypes.ClassifierResult> getClassifierResults() { return classifierResults; } public List<LLResultTypes.ClassifierResult> getClassifierResults() { return classifierResults; }
public List<LLResultTypes.DetectorResult> getDetectorResults() { return detectorResults; } public List<LLResultTypes.DetectorResult> getDetectorResults() { return detectorResults; }
@@ -178,4 +219,6 @@ public class Limelight implements Subsystem {
public LLStatus getStatus() { return status; } public LLStatus getStatus() { return status; }
public LLResult getRawResult() { return result; } public LLResult getRawResult() { return result; }
} }

View File

@@ -1,10 +1,12 @@
package org.firstinspires.ftc.teamcode.utils; package org.firstinspires.ftc.teamcode.variables;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@Config @Config
public class Vars { public class HardwareConfig {
public static boolean USING_LL = false; public static boolean USING_LL = false;
} }