Added April Tag Class and Working Example
This commit is contained in:
@@ -23,6 +23,17 @@ android {
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
repositories {
|
||||
maven {
|
||||
url = 'https://maven.brott.dev/'
|
||||
}
|
||||
}
|
||||
|
||||
dependencies {
|
||||
implementation project(':FtcRobotController')
|
||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
||||
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
||||
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
||||
}
|
||||
|
||||
@@ -13,7 +13,6 @@ The easiest way to create your own OpMode is to copy a Sample OpMode and make it
|
||||
Sample opmodes exist in the FtcRobotController module.
|
||||
To locate these samples, find the FtcRobotController module in the "Project/Android" tab.
|
||||
|
||||
|
||||
Expand the following tree elements:
|
||||
FtcRobotController/java/org.firstinspires.ftc.robotcontroller/external/samples
|
||||
|
||||
@@ -89,8 +88,6 @@ As shown, the current OpMode will NOT appear on the driver station's OpMode list
|
||||
``@Disabled`` annotation which has been included.
|
||||
This line can simply be deleted , or commented out, to make the OpMode visible.
|
||||
|
||||
|
||||
|
||||
## ADVANCED Multi-Team App management: Cloning the TeamCode Module
|
||||
|
||||
In some situations, you have multiple teams in your club and you want them to all share
|
||||
@@ -122,7 +119,8 @@ Note: Some names start with "Team" and others start with "team". This is intent
|
||||
3) the new Team0417 folder, rename the "src/main/java/org/firstinspires/ftc/teamcode" folder
|
||||
to a matching name with a lowercase 'team' eg: "team0417".
|
||||
|
||||
4) In the new Team0417/src/main folder, edit the "AndroidManifest.xml" file, change the line that contains
|
||||
4) In the new Team0417/src/main folder, edit the "AndroidManifest.xml" file, change the line that
|
||||
contains
|
||||
package="org.firstinspires.ftc.teamcode"
|
||||
to be
|
||||
package="org.firstinspires.ftc.team0417"
|
||||
|
||||
@@ -0,0 +1,106 @@
|
||||
package org.firstinspires.ftc.teamcode.subsystems;
|
||||
|
||||
import android.util.Size;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.vision.VisionPortal;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
public class AprilTagWebcam {
|
||||
|
||||
private AprilTagProcessor aprilTagProcessor;
|
||||
private VisionPortal visionPortal;
|
||||
private List<AprilTagDetection> detectedTags = new ArrayList<>();
|
||||
private MultipleTelemetry telemetry;
|
||||
public void init(HardwareMap hwMap, MultipleTelemetry TELE){
|
||||
|
||||
this.telemetry = TELE;
|
||||
|
||||
aprilTagProcessor = new AprilTagProcessor.Builder()
|
||||
.setDrawTagID(true)
|
||||
.setDrawTagOutline(true)
|
||||
.setDrawAxes(true)
|
||||
.setDrawCubeProjection(true)
|
||||
.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES)
|
||||
.build();
|
||||
|
||||
VisionPortal.Builder builder = new VisionPortal.Builder();
|
||||
builder.setCamera(hwMap.get(WebcamName.class, "Webcam 1"));
|
||||
builder.setCameraResolution(new Size(640, 480));
|
||||
builder.addProcessor(aprilTagProcessor);
|
||||
|
||||
visionPortal = builder.build();
|
||||
|
||||
}
|
||||
|
||||
public void update() {
|
||||
detectedTags = aprilTagProcessor.getDetections();
|
||||
}
|
||||
|
||||
public List<AprilTagDetection> getDetectedTags() {
|
||||
return detectedTags;
|
||||
}
|
||||
|
||||
public AprilTagDetection getTagById(int id){
|
||||
for (AprilTagDetection detection : detectedTags) {
|
||||
if (detection.id ==id){
|
||||
return detection;
|
||||
}
|
||||
}
|
||||
return null;
|
||||
}
|
||||
|
||||
public void stop(){
|
||||
if (visionPortal != null){
|
||||
visionPortal.close();
|
||||
}
|
||||
}
|
||||
|
||||
//Helper Functions
|
||||
|
||||
public void displayDetectionTelemetry (AprilTagDetection detectedId){
|
||||
if (detectedId ==null){return;}
|
||||
|
||||
if (detectedId.metadata != null) {
|
||||
telemetry.addLine(String.format("\n==== (ID %d) %s", detectedId.id, detectedId.metadata.name));
|
||||
telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", detectedId.ftcPose.x, detectedId.ftcPose.y, detectedId.ftcPose.z));
|
||||
telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", detectedId.ftcPose.pitch, detectedId.ftcPose.roll, detectedId.ftcPose.yaw));
|
||||
telemetry.addLine(String.format("RBE %6.1f %6.1f %6.1f (inch, deg, deg)", detectedId.ftcPose.range, detectedId.ftcPose.bearing, detectedId.ftcPose.elevation));
|
||||
} else {
|
||||
telemetry.addLine(String.format("\n==== (ID %d) Unknown", detectedId.id));
|
||||
telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detectedId.center.x, detectedId.center.y));
|
||||
}
|
||||
}
|
||||
|
||||
public void displayAllTelemetry (){
|
||||
if (detectedTags ==null){return;}
|
||||
|
||||
telemetry.addData("# AprilTags Detected", detectedTags.size());
|
||||
|
||||
|
||||
for (AprilTagDetection detection : detectedTags) {
|
||||
if (detection.metadata != null) {
|
||||
telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name));
|
||||
telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", detection.ftcPose.x, detection.ftcPose.y, detection.ftcPose.z));
|
||||
telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", detection.ftcPose.pitch, detection.ftcPose.roll, detection.ftcPose.yaw));
|
||||
telemetry.addLine(String.format("RBE %6.1f %6.1f %6.1f (inch, deg, deg)", detection.ftcPose.range, detection.ftcPose.bearing, detection.ftcPose.elevation));
|
||||
} else {
|
||||
telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id));
|
||||
telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y));
|
||||
}
|
||||
} // end for() loop
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
@@ -0,0 +1,37 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.subsystems.AprilTagWebcam;
|
||||
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class AprilTagWebcamExample extends OpMode {
|
||||
|
||||
MultipleTelemetry TELE;
|
||||
AprilTagWebcam aprilTagWebcam = new AprilTagWebcam();
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
aprilTagWebcam.init(hardwareMap, TELE);
|
||||
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
|
||||
aprilTagWebcam.update();
|
||||
aprilTagWebcam.displayAllTelemetry();
|
||||
TELE.update();
|
||||
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user