Skip to content

Commit

Permalink
Changes that were left on laptop made by AlanW and Keerthana
Browse files Browse the repository at this point in the history
  • Loading branch information
Joshua-Smith-42 committed Feb 6, 2024
1 parent e5021f3 commit bb84644
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ public void fillPositions(TeamColor teamColor){
Hashtable<Integer, Pose2d> aprilTagPositions = new Hashtable<>();

private AprilTagProcessor aprilTag;
private TeamPropDetector teamPropDetector;
public TeamPropDetector teamPropDetector;

private VisionPortal visionPortal;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,10 @@ public class CompTeleOp extends QQOpMode{
Node root = TeleopTree.root();

boolean done;

public void init_loop(){
telemetry.addData("right saturation",robot.cameraBack.teamPropDetector.rightSaturation);
telemetry.addData("middle saturation", robot.cameraBack.teamPropDetector.middleSaturation);
}

@Override
public void loop() {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.ftc16072.OpModes.RRTests;
package org.firstinspires.ftc.teamcode.ftc16072.OpModes;

import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.trajectory.Trajectory;
Expand All @@ -9,23 +9,23 @@
import org.firstinspires.ftc.teamcode.ftc16072.Util.TeamPropLocation;

@Autonomous
public class PlacingOnTapeAuto extends OpMode {
Robot robot = new Robot();
public class PlacingOnTapeAuto extends QQOpMode {
Trajectory trajectory;
private enum State {BEGIN, FORWARD,TURN,FORWARD_TO_TAPE, DONE}
State state = State.BEGIN;
TeamPropLocation teamPropLocation;

@Override
public void init() {
robot.makeDriveOnly();
robot.init(hardwareMap);
public void init_loop(){
TeamPropLocation teamPropLocation = robot.cameraBack.getTeamPropPosition();
telemetry.addData("team prop location: ", teamPropLocation);
}

@Override
public void loop() {
robot.nav.updatePoseEstimate();
Pose2d currentPose = robot.nav.getPoseEstimate();
TeamPropLocation teamPropLocation = robot.cameraBack.getTeamPropPosition();

telemetry.addData("team prop location: ", teamPropLocation);
telemetry.addData("STATE", state);
telemetry.addData("POSE", "x = %.2f y = %.2f h = %.1f", currentPose.getX(), currentPose.getY(), Math.toDegrees(currentPose.getHeading()));
switch (state) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,14 @@
import org.opencv.imgproc.Imgproc;
@Config
public class TeamPropDetector implements VisionProcessor {
public static final int SATURATION_THRESHOLD = 1233;
public static final int SATURATION_THRESHOLD = 90;
//makes "detection zones" for each tape zone
TeamPropLocation location = TeamPropLocation.NOT_DETECTED;
public Rect leftTapeDetectionZone = new Rect(100,100,75,75);
public Rect middleTapeDetectionZone = new Rect(250,130,75,75);
public Rect rightTapeDetectionZone = new Rect(400,100,75,75);
public Rect leftTapeDetectionZone = new Rect(20,100,75,75);
public Rect middleTapeDetectionZone = new Rect(200,180,75,75);
public Rect rightTapeDetectionZone = new Rect(550,160,75,75);
public double middleSaturation;
public double rightSaturation;

//submats are smaller portions of the frame that you can get values from
Mat submat = new Mat();
Expand All @@ -35,11 +37,12 @@ public void init(int width, int height, CameraCalibration calibration) {

@Override
public Object processFrame(Mat frame, long captureTimeNanos) {

Imgproc.cvtColor(frame, hsvMat, Imgproc.COLOR_RGB2HSV);


double middleSaturation = getAvgSaturation(hsvMat, middleTapeDetectionZone);
double rightSaturation = getAvgSaturation(hsvMat, rightTapeDetectionZone);
middleSaturation = getAvgSaturation(hsvMat, middleTapeDetectionZone);
rightSaturation = getAvgSaturation(hsvMat, rightTapeDetectionZone);

if(middleSaturation > SATURATION_THRESHOLD) {
location = TeamPropLocation.MIDDLE_SPIKE;
Expand All @@ -65,6 +68,7 @@ protected double getAvgSaturation(Mat input, Rect rect){
return color.val[1];
}


//scales rectangle to
private android.graphics.Rect makeGraphicsRect (Rect rect, float scaleBmpPxToCanvasPx){
int left = Math.round(rect.x*scaleBmpPxToCanvasPx);
Expand Down

0 comments on commit bb84644

Please sign in to comment.