diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/ClawAndWristBot.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/ClawAndWristBot.java index 379ca3a..a796b3b 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/ClawAndWristBot.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/ClawAndWristBot.java @@ -4,7 +4,7 @@ import com.technototes.library.hardware.servo.Servo; import org.firstinspires.ftc.learnbot.subsystems.ClawAndWristSubsystem; -@Config +//@Config public class ClawAndWristBot { public String CLAW1 = "claw1"; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Hardware.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Hardware.java index c3d57cd..fcacf77 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Hardware.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Hardware.java @@ -67,8 +67,8 @@ public Hardware(HardwareMap hwmap) { } this.imu = new IMU( Setup.HardwareNames.IMU, - RevHubOrientationOnRobot.LogoFacingDirection.LEFT, - RevHubOrientationOnRobot.UsbFacingDirection.UP + RevHubOrientationOnRobot.LogoFacingDirection.UP, + RevHubOrientationOnRobot.UsbFacingDirection.FORWARD ); } diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Robot.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Robot.java index ded4604..08343ad 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Robot.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Robot.java @@ -26,8 +26,7 @@ public Robot(Hardware hw) { hw.frMotor, hw.rlMotor, hw.rrMotor, - hw.imu, - hw.distanceSensor + hw.imu ); } if (Setup.Connected.TESTSUBSYSTEM) { diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Setup.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Setup.java index 322a7cc..2ae16bd 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Setup.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/Setup.java @@ -7,7 +7,7 @@ public class Setup { @Config public static class Connected { - public static boolean DRIVEBASE = false; + public static boolean DRIVEBASE = true; public static boolean TESTSUBSYSTEM = false; public static boolean MOTOR = false; public static boolean SERVO = false; @@ -32,4 +32,13 @@ public static class HardwareNames { public static String COLOR = "c"; public static String CAMERA = "camera"; } + + @Config + public static class GlobalSettings { + + public static double STICK_DEAD_ZONE = 0.1; + public static double STRAIGHTEN_SCALE_FACTOR = 0.25; + public static double STRAIGHTEN_RANGE = .15; // Fraction of 45 degrees... + public static double TRIGGER_THRESHOLD = 0.7; + } } diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/AnalogMotorControlCmd.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/AnalogMotorControlCmd.java index d9bc47e..943d9cb 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/AnalogMotorControlCmd.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/AnalogMotorControlCmd.java @@ -5,13 +5,11 @@ import com.technototes.library.logger.Log; import com.technototes.library.logger.Loggable; import java.util.function.DoubleSupplier; +import org.firstinspires.ftc.learnbot.Setup; import org.firstinspires.ftc.learnbot.subsystems.MotorTestSubsystem; -@Config public class AnalogMotorControlCmd implements Command, Loggable { - public static double STICK_DEAD_ZONE = 0.1; - @Log(name = "") public String instruction = "RStick ^/v"; @@ -30,11 +28,13 @@ public AnalogMotorControlCmd(MotorTestSubsystem motorTest, DoubleSupplier axis) @Override public void execute() { double stickPos = ds.getAsDouble(); - if (Math.abs(stickPos) < STICK_DEAD_ZONE) { + if (Math.abs(stickPos) < Setup.GlobalSettings.STICK_DEAD_ZONE) { stickPos = 0; } else { // Scale stickPos from deadzone to 1 and square it to make it a little easier to control - double scaled = (Math.abs(stickPos) - STICK_DEAD_ZONE) / (1 - STICK_DEAD_ZONE); + double scaled = + (Math.abs(stickPos) - Setup.GlobalSettings.STICK_DEAD_ZONE) / + (1 - Setup.GlobalSettings.STICK_DEAD_ZONE); // This gets the sign from stickPos, and puts it on scaled ^ 3 stickPos = Math.copySign(scaled * scaled * scaled, stickPos); } diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/JoystickDriveCommand.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/JoystickDriveCommand.java index bbc4044..37b016f 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/JoystickDriveCommand.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/commands/JoystickDriveCommand.java @@ -1,20 +1,17 @@ package org.firstinspires.ftc.learnbot.commands; -import static org.firstinspires.ftc.learnbot.commands.AnalogMotorControlCmd.STICK_DEAD_ZONE; - import com.acmerobotics.roadrunner.drive.DriveSignal; import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Vector2d; import com.technototes.library.command.Command; import com.technototes.library.control.Stick; -import com.technototes.library.logger.Loggable; import com.technototes.library.util.MathUtils; import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import org.firstinspires.ftc.learnbot.Setup; import org.firstinspires.ftc.learnbot.subsystems.DrivebaseSubsystem; -public class JoystickDriveCommand implements Command, Loggable { +public class JoystickDriveCommand implements Command { public DrivebaseSubsystem subsystem; public DoubleSupplier x, y, r; @@ -26,7 +23,7 @@ public JoystickDriveCommand( DrivebaseSubsystem sub, Stick xyStick, Stick rotStick, - DoubleSupplier strtDrive + DoubleSupplier straightDrive ) { addRequirements(sub); subsystem = sub; @@ -34,7 +31,7 @@ public JoystickDriveCommand( y = xyStick.getYSupplier(); r = rotStick.getXSupplier(); targetHeadingRads = -sub.getExternalHeading(); - driveStraighten = strtDrive; + driveStraighten = straightDrive; } // Use this constructor if you don't want auto-straightening @@ -48,7 +45,7 @@ private double getRotation(double headingInRads) { // Check to see if we're trying to straighten the robot if ( driveStraighten == null || - driveStraighten.getAsDouble() < DrivebaseSubsystem.DriveConstants.TRIGGER_THRESHOLD + driveStraighten.getAsDouble() < Setup.GlobalSettings.TRIGGER_THRESHOLD ) { // No straighten override: return the stick value // (with some adjustment...) @@ -56,19 +53,19 @@ private double getRotation(double headingInRads) { } else { // headingInRads is [0-2pi] double heading = -Math.toDegrees(headingInRads); - // Snap to the closest 90 or 270 degree angle (for going through the depot) double close = MathUtils.closestTo(heading, 0, 90, 180, 270, 360); double offBy = close - heading; // Normalize the error to -1 to 1 double normalized = Math.max(Math.min(offBy / 45, 1.), -1.); // Dead zone of 5 degreesLiftHighJunctionCommand(liftSubsystem) - if (Math.abs(normalized) < STICK_DEAD_ZONE) { + if (Math.abs(normalized) < Setup.GlobalSettings.STRAIGHTEN_RANGE) { return 0.0; } + // Fix the range to be from (abs) dead_zone => 1 to scal from 0 to 1 // Scale it by the cube root, the scale that down by 30% // .9 (about 40 degrees off) provides .96 power => .288 // .1 (about 5 degrees off) provides .46 power => .14 - return Math.cbrt(normalized) * 0.3; + return normalized * Setup.GlobalSettings.STRAIGHTEN_SCALE_FACTOR; // Math.cbrt(normalized) * Setup.GlobalSettings.STRAIGHTEN_SCALE_FACTOR; } } diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/controllers/DriverController.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/controllers/DriverController.java index fca9798..bbda3a9 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/controllers/DriverController.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/controllers/DriverController.java @@ -6,6 +6,7 @@ import com.technototes.library.control.CommandGamepad; import com.technototes.library.control.Stick; import org.firstinspires.ftc.learnbot.Robot; +import org.firstinspires.ftc.learnbot.Setup; import org.firstinspires.ftc.learnbot.commands.EZCmd; import org.firstinspires.ftc.learnbot.commands.JoystickDriveCommand; @@ -24,10 +25,9 @@ public DriverController(CommandGamepad g, Robot r) { gamepad = g; AssignNamedControllerButton(); - // if (Setup.Connected.DRIVEBASE) { - bindDriveControls(); - // } - + if (Setup.Connected.DRIVEBASE) { + bindDriveControls(); + } } private void AssignNamedControllerButton() { diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/auto/Basic.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/auto/Basic.java index 1b47794..fb4bb3d 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/auto/Basic.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/auto/Basic.java @@ -21,8 +21,8 @@ * Wing position: 🪶 * Backstage pos: 🎦 */ -@Config -@Autonomous(name = "Basic Auto") +//@Config +@Autonomous(name = "Basic Auto", preselectTeleOp = "PlainDrive") @SuppressWarnings("unused") public class Basic extends CommandOpMode implements Loggable { diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/AnalogMotorTest.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/AnalogMotorTest.java index e52cb40..7131f67 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/AnalogMotorTest.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/AnalogMotorTest.java @@ -2,6 +2,7 @@ import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.technototes.library.logger.Loggable; import com.technototes.library.structure.CommandOpMode; @@ -10,6 +11,7 @@ import org.firstinspires.ftc.learnbot.Setup; import org.firstinspires.ftc.learnbot.controllers.MotorController; +@Disabled @TeleOp(name = "AnalogMotorTest") @SuppressWarnings("unused") public class AnalogMotorTest extends CommandOpMode implements Loggable { diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/ClawAndWrist.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/ClawAndWrist.java index 2c64c78..61eaedc 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/ClawAndWrist.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/ClawAndWrist.java @@ -2,12 +2,14 @@ import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.technototes.library.logger.Loggable; import com.technototes.library.structure.CommandOpMode; import org.firstinspires.ftc.learnbot.ClawAndWristBot; import org.firstinspires.ftc.learnbot.controllers.ClawAndWristController; +@Disabled @TeleOp(name = "ClawAndWrist") @SuppressWarnings("unused") public class ClawAndWrist extends CommandOpMode implements Loggable { diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/PlainDrive.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/PlainDrive.java index bb68161..7b88743 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/PlainDrive.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/opmodes/tele/PlainDrive.java @@ -3,10 +3,12 @@ import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.technototes.library.command.CommandScheduler; import com.technototes.library.logger.Loggable; import com.technototes.library.structure.CommandOpMode; import org.firstinspires.ftc.learnbot.Hardware; import org.firstinspires.ftc.learnbot.Robot; +import org.firstinspires.ftc.learnbot.commands.DriveCommand; import org.firstinspires.ftc.learnbot.controllers.DriverController; @TeleOp(name = "PlainDrive") diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/ClawAndWristSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/ClawAndWristSubsystem.java index 5cede62..cd5c74d 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/ClawAndWristSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/ClawAndWristSubsystem.java @@ -7,7 +7,7 @@ import com.technototes.library.logger.Loggable; import com.technototes.library.subsystem.Subsystem; -@Config +//@Config public class ClawAndWristSubsystem implements Subsystem, Loggable { public static double CLAW_STEP = 0.1; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/DrivebaseSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/DrivebaseSubsystem.java index ce5b203..5a376ae 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/DrivebaseSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/DrivebaseSubsystem.java @@ -24,23 +24,18 @@ public Pose2d get() { return getPoseEstimate(); } - // Notes from Kevin: - // The 5203 motors when direct driven - // move about 63 inches forward and is measured as roughly 3000 ticks on the encoders - @Config public abstract static class DriveConstants implements MecanumConstants { public static double SLOW_MOTOR_SPEED = 0.6; public static double FAST_MOTOR_SPEED = 1.0; public static double AUTO_MOTOR_SPEED = 0.9; - public static double TRIGGER_THRESHOLD = 0.7; @TicksPerRev - public static final double TICKS_PER_REV = 385.6; // previous: 537.6 + public static final double TICKS_PER_REV = 537.7; // From GoBilda's website @MaxRPM - public static final double MAX_RPM = 435; // 2021: 6000; + public static final double MAX_RPM = 312; public static double MAX_TICKS_PER_SEC = (TICKS_PER_REV * MAX_RPM) / 60.0; @@ -56,17 +51,16 @@ public abstract static class DriveConstants implements MecanumConstants { ); @WheelRadius - public static double WHEEL_RADIUS = 1.88976; // in + public static double WHEEL_RADIUS = 1.88976; // inches "roughly" lol @GearRatio - public static double GEAR_RATIO = 0.6; // output (wheel) speed / input (motor) speed og: 1 / 19.2; + public static double GEAR_RATIO = 1.0; // output (wheel) speed / input (motor) speed - //gear ration is actually .667 but i think it might mess up what we already have @TrackWidth - public static double TRACK_WIDTH = 11.75; // 2021: 10; // in + public static double TRACK_WIDTH = 9.25; // inches @WheelBase - public static double WHEEL_BASE = 8.5; // in + public static double WHEEL_BASE = 9.25; // inches @KV public static double kV = @@ -84,7 +78,7 @@ public abstract static class DriveConstants implements MecanumConstants { // This was 35, which also felt a bit too fast. The bot controls more smoothly now @MaxAccel - public static double MAX_ACCEL = 30; //30 + public static double MAX_ACCEL = 30; // This was 180 degrees @MaxAngleVelo @@ -101,7 +95,7 @@ public abstract static class DriveConstants implements MecanumConstants { public static PIDCoefficients HEADING_PID = new PIDCoefficients(8, 0, 0); @LateralMult - public static double LATERAL_MULTIPLIER = 1.0; // Lateral position is off by 14% + public static double LATERAL_MULTIPLIER = 1.0; // For Mecanum, this was by 1.14 (14% off) @VXWeight public static double VX_WEIGHT = 1; @@ -115,10 +109,7 @@ public abstract static class DriveConstants implements MecanumConstants { @PoseLimit public static int POSE_HISTORY_LIMIT = 100; - // FL - 0.82 - // FR - 0.8 - // RL - 0.1 - // RR - 0.74 + // Helps deal with tired motors public static double AFR_SCALE = 0.9; public static double AFL_SCALE = 0.9; public static double ARR_SCALE = 0.9; @@ -142,34 +133,28 @@ public abstract static class DriveConstants implements MecanumConstants { @Log.Number(name = "RR") public EncodedMotor rr2; - @Log.Number(name = "Dist") - public Rev2MDistanceSensor distanceSensor; - @Log(name = "Turbo") public boolean Turbo = false; @Log(name = "Snail") public boolean Snail = false; - @Log - public String locState = "none"; - @Log(name = "cur heading") double curHeading; - double curDistance; - public DrivebaseSubsystem( EncodedMotor flMotor, EncodedMotor frMotor, EncodedMotor rlMotor, EncodedMotor rrMotor, - IMU imu, - Rev2MDistanceSensor distanceSensor + IMU imu ) { super(flMotor, frMotor, rlMotor, rrMotor, imu, () -> DriveConstants.class); + fl2 = flMotor; + fr2 = frMotor; + rl2 = rlMotor; + rr2 = rrMotor; curHeading = imu.gyroHeading(); - this.distanceSensor = distanceSensor; } @Override @@ -180,10 +165,9 @@ public void periodic() { Pose2d poseVelocity = getPoseVelocity(); poseDisplay = pose.toString() + " : " + - (poseVelocity != null ? poseVelocity.toString() : ""); + (poseVelocity != null ? poseVelocity.toString() : "nullv"); + curHeading = this.imu.gyroHeading(); } - curHeading = this.imu.gyroHeading(); - curDistance = this.distanceSensor.getDistance(DistanceUnit.CM); } public void fast() { @@ -215,24 +199,17 @@ public void setNormalMode() { @Override public void setMotorPowers(double lfv, double lrv, double rrv, double rfv) { - // Slug is Snail mode + "slow down so you don't hit someone's leg" mode - boolean Slug = Snail; - if (curDistance < 30) { - Slug = true; - } - // TODO: Use the stick position to determine how to scale these values // in Turbo mode (If the robot is driving in a straight line, the values are // going to max out at sqrt(2)/2, rather than: We can go faster, but we don't // *always* want to scale faster, only when we're it turbo mode, and when one (or more) // of the control sticks are at their limit - double maxlfvlrv = Math.max(Math.abs(lfv), Math.abs(lrv)); - double maxrfvrrv = Math.max(Math.abs(rfv), Math.abs(rrv)); - double maxall = Math.max(maxlfvlrv, maxrfvrrv); - if (Slug == true) { + double maxlv = Math.max(Math.abs(lfv), Math.abs(lrv)); + double maxrv = Math.max(Math.abs(rfv), Math.abs(rrv)); + double maxall = Math.max(maxlv, maxrv); + if (Snail == true) { maxall = 1.0 / DriveConstants.SLOW_MOTOR_SPEED; - } - if (Turbo == false && Slug == false) { + } else if (Turbo == false) { maxall = 1.0 / DriveConstants.AUTO_MOTOR_SPEED; } leftFront.setVelocity( diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/FlywheelSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/FlywheelSubsystem.java index a7b82d7..a11a71c 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/FlywheelSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/FlywheelSubsystem.java @@ -6,7 +6,7 @@ import com.technototes.library.logger.Loggable; import com.technototes.library.subsystem.Subsystem; -@Config +//@Config public class FlywheelSubsystem implements Subsystem, Loggable { public static double INTAKE_SPEED = -0.8; //tested 1/9/24 diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/IntakeSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/IntakeSubsystem.java index d4a4b7e..e56a9bd 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/IntakeSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/IntakeSubsystem.java @@ -10,7 +10,7 @@ import com.technototes.library.logger.Loggable; import com.technototes.library.subsystem.Subsystem; -@Config +//@Config public class IntakeSubsystem implements Subsystem, Loggable { public static double MIN_INTAKE_SPEED = -1; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/MotorTestSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/MotorTestSubsystem.java index 7ca31e9..5c9e949 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/MotorTestSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/MotorTestSubsystem.java @@ -11,7 +11,7 @@ import com.technototes.library.subsystem.Subsystem; import org.firstinspires.ftc.learnbot.Hardware; -@Config +//@Config public class MotorTestSubsystem implements Subsystem, Loggable { public static double POWER_CHANGE = 0.02; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/PlacementSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/PlacementSubsystem.java index ca67281..bdd5f84 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/PlacementSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/PlacementSubsystem.java @@ -9,7 +9,7 @@ import com.technototes.library.subsystem.Subsystem; import org.firstinspires.ftc.learnbot.Hardware; -@Config +//@Config public class PlacementSubsystem implements Subsystem, Loggable { public static double INTAKE_SPEED = .3; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/TestSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/TestSubsystem.java index b3d71e3..f0b2ee0 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/TestSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/TestSubsystem.java @@ -11,7 +11,7 @@ import org.firstinspires.ftc.learnbot.Hardware; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; -@Config +//@Config public class TestSubsystem implements Subsystem, Loggable { public static int DISTANCE = 10; // centimeters! diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionPipeline.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionPipeline.java index 5538d19..af461e5 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionPipeline.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionPipeline.java @@ -19,7 +19,7 @@ import org.opencv.imgproc.Imgproc; import org.openftc.easyopencv.OpenCvPipeline; -@Config +//@Config public class VisionPipeline extends OpenCvPipeline implements Supplier, Loggable { public Alliance alliance; @@ -33,10 +33,10 @@ public VisionPipeline(Alliance teamAlliance, StartingPosition startSide) { boolean StartingPosition = middleDetected; } - @Config + //@Config public static class VisionConstants { - @Config + //@Config public static class Left { public static int X = 10; @@ -45,7 +45,7 @@ public static class Left { public static int HEIGHT = 90; } - @Config + //@Config public static class Middle { public static int X = 130; diff --git a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionSubsystem.java b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionSubsystem.java index fc91627..7f2bb7d 100644 --- a/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionSubsystem.java +++ b/LearnBot/src/main/java/org/firstinspires/ftc/learnbot/subsystems/VisionSubsystem.java @@ -10,7 +10,7 @@ public class VisionSubsystem implements Subsystem, Loggable { - @Config + //@Config public static class VisionSubsystemConstants { // This is a super-low res image. I don't think we need higher resolution... diff --git a/bun.lockb b/bun.lockb index 766df45..fa93227 100755 Binary files a/bun.lockb and b/bun.lockb differ