Skip to content

Commit

Permalink
Integrated tensorflow into our autonomous class. TODO: map out route …
Browse files Browse the repository at this point in the history
…for autonomous and implement.
  • Loading branch information
JimmyLi2020 committed Sep 26, 2019
2 parents 4db8cfc + 5ad97c7 commit 4537d8b
Show file tree
Hide file tree
Showing 5 changed files with 117 additions and 58 deletions.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,6 @@ public class TensorflowTest extends LinearOpMode {

private TFObjectDetector tfod;

DcMotor motorFL;
DcMotor motorFR;
DcMotor motorBL;
DcMotor motorBR;

@Override
public void runOpMode() {
initVuforia();
Expand Down Expand Up @@ -57,13 +52,13 @@ public void runOpMode() {
telemetry.addData(String.format(" right,bottom (%d)", i), "%.03f , %.03f",
recognition.getRight(), recognition.getBottom());
}
telemetry.update();
}
}
}
if (tfod != null) {
tfod.shutdown();
}
telemetry.update();
}

/**
Expand Down Expand Up @@ -96,37 +91,6 @@ private void initTfod() {
tfod.loadModelFromAsset(TFOD_MODEL_ASSET, LABEL_FIRST_ELEMENT, LABEL_SECOND_ELEMENT);
}

public void initMotors() {
motorFL = hardwareMap.get(DcMotor.class, "motorFL");
motorFR = hardwareMap.get(DcMotor.class, "motorFR");
motorBL = hardwareMap.get(DcMotor.class, "motorBL");
motorBR = hardwareMap.get(DcMotor.class, "motorBR");

motorFL.setDirection(DcMotorSimple.Direction.REVERSE);
motorFR.setDirection(DcMotorSimple.Direction.FORWARD);
motorBL.setDirection(DcMotorSimple.Direction.REVERSE);
motorBR.setDirection(DcMotorSimple.Direction.FORWARD);
}

public void moveForward(double power) {
motorFL.setPower(power);
motorFR.setPower(power);
motorBL.setPower(power);
motorBR.setPower(power);
}

public void rotateLeft(double power) {
motorFL.setPower(-power);
motorFL.setPower(-power);
motorFL.setPower(power);
motorFL.setPower(power);
}

public void straifLeft(double power) {
motorFL.setPower(-power);
motorFR.setPower(power);
motorBL.setPower(power);
motorBR.setPower(-power);
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,27 @@
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;

import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
import org.firstinspires.ftc.robotcore.external.tfod.TFObjectDetector;

import java.util.List;

@Autonomous(name = "TestAutonomous")
public class TestAutonomous extends LinearOpMode {

private static final String TFOD_MODEL_ASSET = "Skystone.tflite";
private static final String LABEL_FIRST_ELEMENT = "Stone";
private static final String LABEL_SECOND_ELEMENT = "Skystone";
private static final String VUFORIA_KEY = "ATUNNu//////AAABmU6BPERoN0USgSQzxPQZ8JYg9RVnQhKO6YEHbNnOhkfL/iNrji3x9vzFkKsBgVzWgwH72G6eXpb3VCllKTrt1cD3gvQXZ48f+5EN43eYUQ3nuP3943NZB822XzV1djS3s6wDdaiS20PErO5K7lZUGyf9Z4Tb2TliOXv/ZoxUvwNQ/ndRjN344G0TAo8PUja0V3x2WKk+mCJavoZIgmOqgaitgmg5jim/aWBL2yk0a/QpqbP87KQfGn69zpisDBc98xdGPdSFj9ENkU9WTMem9UgnOFPgpdrHV5Zr5IpQH1jxLZIvwGuKOT97npm54kIvnJM0dzhBVA+s95JA3cxyac5ArHUYVtDePwlExuekZy9l";

private VuforiaLocalizer vuforia;

private TFObjectDetector tfod;

DcMotor motorFL;
DcMotor motorFR;
DcMotor motorBL;
Expand All @@ -25,20 +42,43 @@ public class TestAutonomous extends LinearOpMode {
final double DRIVE_GEAR_REDUCTION = 2.0; // This is < 1.0 if geared UP
final double WHEEL_DIAMETER_INCHES = 4.0; // For figuring circumference
final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) / (WHEEL_DIAMETER_INCHES * 3.1415);
final double DRIVE_SPEED = 0.4;
final double DRIVE_SPEED = 0.6;
final double TURN_SPEED = 0.4;

private final String[] actions = {"forward", "backward", "left", "right", "rotate"};

@Override
public void runOpMode() {

initVuforia();

if (ClassFactory.getInstance().canCreateTFObjectDetector())
initTfod();
else {
telemetry.addData("Sorry!", "This device is not compatible with TFOD");
telemetry.update();
stop();
}

tfod.activate();

initMotors();
telemetry.addData("status", "Initialized");

waitForStart();

doAction("forward", 5.0);

doAction("forward", 7.0);
doAction("left", 5.0);

// while(opModeIsActive())
// {
// updateTensorflow();
//
// }

doAction("backward", 5.0);
doAction("rotate", 10.0);
doAction("rotate", 10.0); // almost 360
doAction("left", 5.0);
doAction("right", 5.0);

Expand Down Expand Up @@ -69,28 +109,49 @@ public void initMotors() {
motorBR.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}

public void doAction(String a, double d) {
int action = -1;
public void moveForwardRaw(double power) {
motorFL.setPower(Range.clip(calibFL * power, -1, 1));
motorFR.setPower(Range.clip(calibFR * power, -1, 1));
motorBL.setPower(Range.clip(calibBL * power, -1, 1));
motorBR.setPower(Range.clip(calibBR * power, -1, 1));
}

public void rotateLeftRaw(double power) {
motorFL.setPower(calibFL * -power);
motorFR.setPower(calibFR * power);
motorBL.setPower(calibBL * -power);
motorBR.setPower(calibBR * power);
}

public void straifLeftRaw(double power) {
motorFL.setPower(calibFL * -power);
motorFR.setPower(calibFR * -power);
motorBL.setPower(calibBR * power);
motorBR.setPower(calibBR * power);
}

public void doAction(String action, double distance) {
int actionInt = -1;
for (int i = 0; i < 5; i++) {
if (a.equals(actions[i]))
action = i;
if (action.equals(actions[i]))
actionInt = i;
}

switch (action) {
switch (actionInt) {
case 0:
moveForward(d);
moveForward(distance);
break;
case 1:
moveForward(-d);
moveForward(-distance);
break;
case 2:
straifLeft(d);
straifLeft(distance);
break;
case 3:
straifLeft(-d);
straifLeft(-distance);
break;
case 4:
rotateLeft(d);
rotateLeft(distance);
break;
}
}
Expand Down Expand Up @@ -151,7 +212,7 @@ public void encoderDrive(double speed,
while (opModeIsActive() &&
(runtime.seconds() < timeoutS) &&
(motorFL.isBusy() || motorFR.isBusy() || motorBL.isBusy() || motorBR.isBusy())) {

updateTensorflow();
}

// Stop all motion;
Expand All @@ -172,6 +233,46 @@ public void encoderDrive(double speed,
}


private void initVuforia() {
/*
* Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
*/
VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters();

parameters.vuforiaLicenseKey = VUFORIA_KEY;
parameters.cameraDirection = VuforiaLocalizer.CameraDirection.BACK;

// Instantiate the Vuforia engine
vuforia = ClassFactory.getInstance().createVuforia(parameters);

// Loading trackables is not necessary for the TensorFlow Object Detection engine.
}

private void initTfod() {
int tfodMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
"tfodMonitorViewId", "id", hardwareMap.appContext.getPackageName());
TFObjectDetector.Parameters tfodParameters = new TFObjectDetector.Parameters(tfodMonitorViewId);
tfodParameters.minimumConfidence = 0.8;
tfod = ClassFactory.getInstance().createTFObjectDetector(tfodParameters, vuforia);
tfod.loadModelFromAsset(TFOD_MODEL_ASSET, LABEL_FIRST_ELEMENT, LABEL_SECOND_ELEMENT);
}

private void updateTensorflow() {
List<Recognition> updatedRecognitions = tfod.getUpdatedRecognitions();
if (updatedRecognitions != null) {
telemetry.addData("# Object Detected", updatedRecognitions.size());
int i = 0;
for (Recognition recognition : updatedRecognitions) {
telemetry.addData(String.format("label (%d)", i), recognition.getLabel());
telemetry.addData(String.format(" left,top (%d)", i), "%.03f , %.03f",
recognition.getLeft(), recognition.getTop());
telemetry.addData(String.format(" right,bottom (%d)", i), "%.03f , %.03f",
recognition.getRight(), recognition.getBottom());
}
}
}




}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import java.lang.Math;
import com.qualcomm.robotcore.util.Range;

@TeleOp(name = "MechTeleOpAvgAtpt")
@TeleOp(name = "MechTeleOp")
public class MechTeleOp extends OpMode {
DcMotor motorFL;
DcMotor motorFR;
Expand Down
1 change: 0 additions & 1 deletion gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
#Mon Sep 23 01:25:20 EDT 2019
distributionBase=GRADLE_USER_HOME
distributionPath=wrapper/dists
zipStoreBase=GRADLE_USER_HOME
Expand Down

0 comments on commit 4537d8b

Please sign in to comment.