From c73434ad26b8b1dc867ee9d012c73f2625763bdc Mon Sep 17 00:00:00 2001 From: Thomas <@TOMMY> Date: Thu, 30 Nov 2023 10:57:43 -0600 Subject: [PATCH] Claw, Gantry, and Lift --- TeamCode/src/main/java/opmodes/AutoBase.java | 3 +-- .../java/org/firstinspires/ftc/teamcode/hardware/Camera.java | 4 ++-- .../org/firstinspires/ftc/teamcode/hardware/RobotConfig.java | 4 ++-- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/TeamCode/src/main/java/opmodes/AutoBase.java b/TeamCode/src/main/java/opmodes/AutoBase.java index 2dfa830..c3a7c5f 100644 --- a/TeamCode/src/main/java/opmodes/AutoBase.java +++ b/TeamCode/src/main/java/opmodes/AutoBase.java @@ -74,7 +74,6 @@ public abstract class AutoBase extends LinearOpMode { propRight(); break; } - moveToBackstage(); prepareToScore(); scorePreloadedPixel(); @@ -129,7 +128,7 @@ public abstract class AutoBase extends LinearOpMode { delta = APRIL_TAG_RIGHT_DELTA; break; } - double distance = this.robot.getCamera().getDistanceToAprilTag(2, 25, 5); + double distance = this.robot.getCamera().getDistanceToAprilTag(this.alliance == CenterStageCommon.Alliance.Blue ? 2:5, 25, 5); Vector2d target = new Vector2d(this.robot.getDrive().getPoseEstimate().getX() + (distance - SCORING_DISTANCE_FROM_APRIL_TAG), this.robot.getDrive().getPoseEstimate().getY() + delta); TrajectorySequenceBuilder builder = this.robot.getTrajectorySequenceBuilder(); builder.lineToConstantHeading(target); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/Camera.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/Camera.java index 1c5c7bb..886eb54 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/Camera.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/Camera.java @@ -18,8 +18,8 @@ import org.opencv.core.Point; @Config public class Camera { - public static float PROP_REJECTION_VERTICAL_UPPER = 175; - public static float PROP_REJECTION_VERTICAL_LOWER = 300; + public static float PROP_REJECTION_VERTICAL_UPPER = 250; + public static float PROP_REJECTION_VERTICAL_LOWER = 370; private PropDetectionPipeline prop; private AprilTagProcessor aprilTag; private VisionPortal visionPortal; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/RobotConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/RobotConfig.java index da239fe..82b1dc2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/RobotConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/hardware/RobotConfig.java @@ -66,8 +66,8 @@ public class RobotConfig { // Vision public static double CAMERA_OFFSET_X = 0f; - public static double DETECTION_AREA_MIN = 0.02f; - public static double DETECTION_AREA_MAX = 0.3f; + public static double DETECTION_AREA_MIN = 0.01f; + public static double DETECTION_AREA_MAX = 0.2f; public static double DETECTION_LEFT_X = 0; public static double DETECTION_CENTER_X = .5; public static double DETECTION_RIGHT_X = 1;