Skip to content
This repository has been archived by the owner on Jan 19, 2025. It is now read-only.

Commit

Permalink
Aka random stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
Akachukwuegbosimba committed Dec 9, 2023
1 parent 14f7484 commit 4450d5d
Show file tree
Hide file tree
Showing 9 changed files with 334 additions and 45 deletions.
86 changes: 85 additions & 1 deletion EncoderAuto.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Servo;

import org.firstinspires.ftc.teamcode.modules.DriveTrain;
import org.firstinspires.ftc.teamcode.modules.Webcams.AprilTagWebcam;
import org.firstinspires.ftc.teamcode.modules.Webcams.Webcam;
import org.firstinspires.ftc.teamcode.modules.output.LinearSlide;
import org.firstinspires.ftc.teamcode.modules.output.OutputPivot;
import org.firstinspires.ftc.teamcode.util.TelemetryWrapper;

public class EncoderAuto extends LinearOpMode {
protected static final boolean LEFT = false;
Expand All @@ -10,12 +19,87 @@ public class EncoderAuto extends LinearOpMode {
*/
private final boolean sideOfField;

private DriveTrain driveTrain;
private LinearSlide linearSlide;
private OutputPivot pivot;
private DcMotor intakeWheel;
private Servo firstPixel;
private Servo secondPixel;



private Webcam randomizationWebcam;

private AprilTagWebcam aprilTagWebcam;


public EncoderAuto(boolean sideOfField) {
this.sideOfField = sideOfField;
}

@Override
public void runOpMode() {
public void runOpMode() throws InterruptedException {
TelemetryWrapper.init(telemetry, 20);

TelemetryWrapper.setLine(1, "Autonomous " + "\t Initializing");

driveTrain = new DriveTrain(this);
driveTrain.init(hardwareMap);
linearSlide = new LinearSlide("OutputSlide", 0.5);
pivot = new OutputPivot("OutputPivot");
intakeWheel = hardwareMap.get(DcMotor.class, "intakeWheel");
firstPixel = hardwareMap.get(Servo.class, "FirstPixel");
firstPixel = hardwareMap.get(Servo.class, "SecondPixel");
aprilTagWebcam = new AprilTagWebcam();
aprilTagWebcam.init(hardwareMap);

waitForStart();

int loc = detectTape(randomizationWebcam);
// Move one tile
driveTrain.translate(0.8, 0, 24, 0, 10);

// Turn to place position
driveTrain.translate(0.8, 0, 0, 45*loc, 10);

// Spit out pixel
intakeWheel.setPower(-0.5);
wait(1);
intakeWheel.setPower(0);

// Turn to neutral position
driveTrain.translate(0.8, 0, 0, -45*loc, 10);

// Turn to backdrop
driveTrain.translate(0.8, 0, 0, 90, 10);

// Drive halfway to the backdrop
driveTrain.translate(0.8, 0, 40, 0, 10);

// Use april tag to navigate the rest of the way
driveTrain.move(0, 0.8, 0, 1);

double[] currentPos = aprilTagWebcam.detectIter();
while (currentPos[0] < 120){
currentPos = aprilTagWebcam.detectIter();
}

driveTrain.stop();

driveTrain.move(0.8 * loc, 0, 0, 1);

while(Math.abs(currentPos[1] - 36+loc*10) < 0.3){
currentPos = aprilTagWebcam.detectIter();
}

driveTrain.stopStayInPlace();




}

public int detectTape(Webcam webcam){
return 0;
}
}
27 changes: 27 additions & 0 deletions HybridAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;

import org.firstinspires.ftc.teamcode.modules.DriveTrain;

public class HybridAuto extends LinearOpMode {

private DriveTrain driveTrain;
protected static final boolean LEFT = false;
protected static final boolean RIGHT = true;
/**
* Whether the robot is on the left or right side of the alliance station.
*/
private final boolean sideOfField;

public HybridAuto(boolean sideOfField) {
this.sideOfField = sideOfField;
}

@Override
public void runOpMode() {
DriveTrain drivetrain = new DriveTrain(this);
driveTrain.init(hardwareMap);

}
}
23 changes: 17 additions & 6 deletions TeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@ public void runOpMode() {
gp2 = new ButtonHelper(gamepad2);
driveTrain = new DriveTrain(this);
intakeWheel = hardwareMap.get(DcMotor.class, "intakeWheel");
// outputSlide = new LinearSlide("outputSlide", 0.5);
pivot = new OutputPivot("outputPivot");
outputSlide = new LinearSlide("linearSlide", 0.5);
// pivot = new OutputPivot("outputPivot");
outputClaw = new Claw("outputClaw");
driveTrain.init(hardwareMap);
// outputSlide.init(hardwareMap);
pivot.init(hardwareMap);
outputSlide.init(hardwareMap);
// pivot.init(hardwareMap);
outputClaw.init(hardwareMap);


Expand All @@ -49,20 +49,31 @@ public void runOpMode() {
waitForStart();

while (opModeIsActive()) {
TelemetryWrapper.setLine(2, "LeftSlidePos" + outputSlide.getCurrentPosition()[0]);
TelemetryWrapper.setLine(3, "RightSlidePos" + outputSlide.getCurrentPosition()[1]);
TelemetryWrapper.setLine(4, "PivotServoPos" + outputClaw.getPosition());
// Update ButtonHelper
gp1.update();
gp2.update();

// DriveTrain wheels
driveTrain.move(-gamepad1.left_stick_x, -gamepad1.left_stick_y, gamepad1.right_stick_x, speedMultiplier);

// outputSlide.moveUsingEncoder(gamepad2.left_stick_y * 0.5);
outputSlide.moveUsingEncoder(gamepad2.left_stick_y * 0.5);
intakeWheel.setPower((gamepad2.right_trigger - gamepad2.left_trigger) * 0.8);
pivot.moveUsingEncoder(-gamepad2.right_stick_y * 0.5);
// pivot.moveUsingEncoder(-gamepad2.right_stick_y * 0.5);

if (gp2.pressing(ButtonHelper.dpad_up)) {
outputClaw.toggleClaw();
}

// if (gp2.pressed(ButtonHelper.dpad_up)) {
// outputClaw.moveClaw(0.3);
// }else if (gp2.pressed(ButtonHelper.dpad_down)){
// outputClaw.moveClaw(-0.3);
// }else{
// outputClaw.moveClaw(0);
// }
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
* SOFTWARE.
*/

package org.firstinspires.ftc.teamcode;
package org.firstinspires.ftc.teamcode.modules.Webcams;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
Expand All @@ -33,7 +33,6 @@
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;
import org.openftc.easyopencv.OpenCvInternalCamera;

import java.util.ArrayList;

Expand Down
12 changes: 6 additions & 6 deletions AprilTagDemo.java → modules/Webcams/AprilTagDemo.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
* SOFTWARE.
*/

package org.firstinspires.ftc.teamcode;
package org.firstinspires.ftc.teamcode.modules.Webcams;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
Expand Down Expand Up @@ -47,13 +47,13 @@ public class AprilTagDemo extends LinearOpMode
// UNITS ARE PIXELS
// NOTE: this calibration is for the C920 webcam at 800x448.
// You will need to do your own calibration for other configurations!
double fx = 578.272;
double fy = 578.272;
double cx = 402.145;
double cy = 221.506;
double fx = 821.993;
double fy = 821.993;
double cx = 330.489;
double cy = 248.997f;

// UNITS ARE METERS
double tagsize = 0.166;
double tagsize = 0.127;

int numFramesWithoutDetection = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
* SOFTWARE.
*/

package org.firstinspires.ftc.teamcode;
package org.firstinspires.ftc.teamcode.modules.Webcams;

import org.opencv.calib3d.Calib3d;
import org.opencv.core.CvType;
Expand Down
148 changes: 148 additions & 0 deletions modules/Webcams/AprilTagWebcam.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,148 @@
package org.firstinspires.ftc.teamcode.modules.Webcams;

import android.util.Size;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.HardwareMap;

import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
import org.firstinspires.ftc.teamcode.modules.Webcams.AprilTagDetectionPipeline;
import org.firstinspires.ftc.vision.VisionPortal;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
import org.firstinspires.ftc.vision.apriltag.AprilTagGameDatabase;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;

import java.util.ArrayList;
import java.util.List;

public class AprilTagWebcam {

OpenCvCamera camera;
AprilTagDetectionPipeline aprilTagDetectionPipeline;

static final double FEET_PER_METER = 3.28084;

// Lens intrinsics
// UNITS ARE PIXELS
// NOTE: this calibration is for the C920 webcam at 800x448.
// You will need to do your own calibration for other configurations!
double fx = 578.272;
double fy = 578.272;
double cx = 402.145;
double cy = 221.506;

private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera

/**
* The variable to store our instance of the AprilTag processor.
*/
private AprilTagProcessor aprilTag;

/**
* The variable to store our instance of the vision portal.
*/
private VisionPortal visionPortal;

/**
* Initialize the AprilTag processor.
*/
public void init(HardwareMap hardwareMap) {

// Create the AprilTag processor.
aprilTag = new AprilTagProcessor.Builder()
.setDrawAxes(false)
.setDrawCubeProjection(false)
.setDrawTagOutline(true)
.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11)
.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary())
.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES)

// == CAMERA CALIBRATION ==
// If you do not manually specify calibration parameters, the SDK will attempt
// to load a predefined calibration for your camera.
.setLensIntrinsics(fx, fy, cx, cy)
// ... these parameters are fx, fy, cx, cy.

.build();

// Adjust Image Decimation to trade-off detection-range for detection-rate.
// eg: Some typical detection data using a Logitech C920 WebCam
// Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second
// Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second
// Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default)
// Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default)
// Note: Decimation can be changed on-the-fly to adapt during a match.
aprilTag.setDecimation(3);

// Create the vision portal by using a builder.
VisionPortal.Builder builder = new VisionPortal.Builder();

// Set the camera (webcam vs. built-in RC phone camera).
if (USE_WEBCAM) {
builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1"));
} else {
builder.setCamera(BuiltinCameraDirection.BACK);
}

// Choose a camera resolution. Not all cameras support all resolutions.
builder.setCameraResolution(new Size(640, 480));

// Enable the RC preview (LiveView). Set "false" to omit camera monitoring.
builder.enableLiveView(true);

// Set the stream format; MJPEG uses less bandwidth than default YUY2.
builder.setStreamFormat(VisionPortal.StreamFormat.YUY2);

// Choose whether or not LiveView stops if no processors are enabled.
// If set "true", monitor shows solid orange screen if no processors enabled.
// If set "false", monitor shows camera view without annotations.
builder.setAutoStopLiveView(false);

// Set and enable the processor.
builder.addProcessor(aprilTag);

// Build the Vision Portal, using the above settings.
visionPortal = builder.build();

// Disable or re-enable the aprilTag processor at any time.
visionPortal.setProcessorEnabled(aprilTag, true);

} // end method initAprilTag()


/**
* Add telemetry about AprilTag detections.
*/
public double[] detectIter() {

List<org.firstinspires.ftc.vision.apriltag.AprilTagDetection> currentDetections = aprilTag.getDetections();

double avg_z = 0;
double avg_y = 0;
double avg_x = 0;
// Step through the list of detections and display info for each one.
for (AprilTagDetection detection : currentDetections) {
if (detection.metadata != null) {
avg_z += detection.metadata.fieldPosition.get(2) - detection.ftcPose.z;
avg_y += detection.metadata.fieldPosition.get(1) - detection.ftcPose.y;
avg_x += detection.metadata.fieldPosition.get(0) - detection.ftcPose.x;
}
} // end for() loop

avg_z /= currentDetections.size();
avg_y /= currentDetections.size();
avg_x /= currentDetections.size();

return new double[]{avg_x, avg_y, avg_z};

} // end method telemetryAprilTag()
}
Loading

0 comments on commit 4450d5d

Please sign in to comment.