-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathAprilTagManualPosePID.java
More file actions
134 lines (106 loc) · 5.06 KB
/
AprilTagManualPosePID.java
File metadata and controls
134 lines (106 loc) · 5.06 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
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.AprilTagLibrary;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
import java.util.List;
@TeleOp(name = "AprilTag Manual Pose (Fixed PID)", group = "AprilTag")
public class AprilTagManualPosePID extends LinearOpMode {
private static final double CUSTOM_TAG_SIZE_INCHES = 4.5;
private static final int CUSTOM_TAG_ID = 20;
private AprilTagProcessor aprilTagProcessor;
private VisionPortal visionPortal;
private DcMotorEx mymotor;
private ElapsedTime timer = new ElapsedTime();
// --- PID Constants ---
private double Kp = 1.0;
private double Ki = 0.0;
private double Kd = 0.0;
// --- PID Variables ---
private double integralSum = 0;
private double lastError = 0;
private double calculatePID(double targetPosition, double currentPosition) {
double error = targetPosition- currentPosition;
double dt = timer.seconds();
timer.reset();
double proportional = Kp * error;
integralSum += error * dt;
double integral = Ki * integralSum;
double derivative = (dt > 0) ? Kd * (error - lastError) / dt : 0;
lastError = error;
return proportional + integral + derivative;
}
@Override
public void runOpMode() {
// 1. Define a custom AprilTag library
AprilTagLibrary customAprilTagLibrary = new AprilTagLibrary.Builder()
.addTag(CUSTOM_TAG_ID, "CustomTag", CUSTOM_TAG_SIZE_INCHES, DistanceUnit.INCH)
.addTag(24, "Custom2tag", CUSTOM_TAG_SIZE_INCHES, DistanceUnit.INCH)
.build();
// 2. Create AprilTag processor
aprilTagProcessor = new AprilTagProcessor.Builder()
.setTagLibrary(customAprilTagLibrary)
.build();
// 3. Set up vision portal
visionPortal = new VisionPortal.Builder()
.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1"))
.addProcessor(aprilTagProcessor)
.build();
// 4. Configure motor
mymotor = hardwareMap.get(DcMotorEx.class, "motor");
mymotor.setPower(0);
mymotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
mymotor.setDirection(DcMotorSimple.Direction.FORWARD);
mymotor.setMode(DcMotorEx.RunMode.STOP_AND_RESET_ENCODER);
mymotor.setMode(DcMotorEx.RunMode.RUN_WITHOUT_ENCODER);
telemetry.addData("Status", "Initialized");
telemetry.update();
waitForStart();
timer.reset();
while (opModeIsActive()) {
List<AprilTagDetection> currentDetections = aprilTagProcessor.getDetections();
telemetry.addData("# AprilTags Detected", currentDetections.size());
if (currentDetections.size() == 0) {
// No tag visible → stop and reset PID
mymotor.setPower(0);
mymotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
integralSum = 0;
lastError = 0;
telemetry.addLine("No tag detected → motor stopped");
} else {
// Process first visible tag (you can choose which one to prioritize)
AprilTagDetection detection = currentDetections.get(0);
if (detection.metadata != null) {
telemetry.addLine(String.format("Tag ID: %d (%s)", detection.id, detection.metadata.name));
telemetry.addLine(String.format("Pose XYZ (in.): x=%6.1f y=%6.1f z=%6.1f",
detection.ftcPose.x, detection.ftcPose.y, detection.ftcPose.z));
double yaw = detection.ftcPose.yaw; // rotation error (degrees)
double targetYaw = 0; // goal = centered tag
// PID control for yaw
double motorPower = calculatePID(targetYaw, yaw);
// Add a deadband
if (Math.abs(yaw) < 5.0) {
motorPower = 0;
}
// Clip motor power for safety
motorPower = Math.max(-0.25, Math.min(0.25, motorPower));
mymotor.setPower(motorPower);
telemetry.addData("Yaw", "%.2f", yaw);
telemetry.addData("Motor Power", "%.2f", motorPower);
}
}
telemetry.update();
sleep(20);
}
// Stop camera safely
visionPortal.close();
}
}