-
Notifications
You must be signed in to change notification settings - Fork 0
/
TrajectorySequenceTest.java
199 lines (168 loc) · 7.74 KB
/
TrajectorySequenceTest.java
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
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
package org.firstinspires.ftc.teamcode;
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.geometry.Vector2d;
import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.DistanceSensor;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.cameracode.AprilTagDetectionPipeline;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequence;
import org.openftc.apriltag.AprilTagDetection;
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;
import java.util.ArrayList;
@Disabled
@Autonomous(name = "TrajectorySequenceTest")
public class TrajectorySequenceTest extends LinearOpMode {
private DcMotorEx arm;
private Servo wrist;
private Servo spooky;
private Servo claw;
private DistanceSensor distance;
private VoltageSensor ControlHub_VoltageSensor;
private ColorSensor clawSensor;
private final double ticks_per_degree = 2400;
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;
// UNITS ARE METERS
double tagsize = 0.166;
int tag1 = 0;// Tag ID 18 from the 36h11 family, https://github.com/AprilRobotics/apriltag-imgs/blob/master/tag36h11/tag36_11_00000.png
int tag2 = 1;//https://github.com/AprilRobotics/apriltag-imgs/blob/master/tag36h11/tag36_11_00001.png
int tag3 = 2;//https://github.com/AprilRobotics/apriltag-imgs/blob/master/tag36h11/tag36_11_00002.png
AprilTagDetection tagOfInterest = null;
@Override
public void runOpMode() {
int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
camera = OpenCvCameraFactory.getInstance().createWebcam(hardwareMap.get(WebcamName.class, "Webcam 1"), cameraMonitorViewId);
aprilTagDetectionPipeline = new AprilTagDetectionPipeline(tagsize, fx, fy, cx, cy);
camera.setPipeline(aprilTagDetectionPipeline);
camera.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener()
{
@Override
public void onOpened()
{
camera.startStreaming(1280,720, OpenCvCameraRotation.UPRIGHT);
}
@Override
public void onError(int errorCode)
{
}
});
telemetry.setMsTransmissionInterval(50);
while (!isStarted() && !isStopRequested())
{
ArrayList<AprilTagDetection> currentDetections = aprilTagDetectionPipeline.getLatestDetections();
if(currentDetections.size() != 0)
{
boolean tagFound = false;
for(AprilTagDetection tag : currentDetections)
{
if(tag.id == tag1 ||tag.id == tag2 ||tag.id == tag3 )
{
tagOfInterest = tag;
tagFound = true;
break;
}
}
if(tagFound)
{
telemetry.addLine("Tag of interest is in sight!\n\nLocation data:");
tagToTelemetry(tagOfInterest);
}
else
{
telemetry.addLine("Don't see tag of interest :(");
if(tagOfInterest == null)
{
telemetry.addLine("(The tag has never been seen)");
}
else
{
telemetry.addLine("\nBut we HAVE seen the tag before; last seen at:");
tagToTelemetry(tagOfInterest);
}
}
}
else
{
telemetry.addLine("Don't see tag of interest :(");
if(tagOfInterest == null)
{
telemetry.addLine("(The tag has never been seen)");
}
else
{
telemetry.addLine("\nBut we HAVE seen the tag before; last seen at:");
tagToTelemetry(tagOfInterest);
}
}
telemetry.update();
sleep(20);
}
SampleMecanumDrive drive = new SampleMecanumDrive(hardwareMap);
drive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
arm = hardwareMap.get(DcMotorEx.class, "arm");
wrist = hardwareMap.get(Servo.class, "wrist");
spooky = hardwareMap.get(Servo.class, "spooky");
claw = hardwareMap.get(Servo.class, "claw");
distance = hardwareMap.get(DistanceSensor.class, "distance");
clawSensor = hardwareMap.get(ColorSensor.class, "claw color");
ControlHub_VoltageSensor = hardwareMap.get(VoltageSensor.class, "Control Hub");
arm.setDirection(DcMotorSimple.Direction.REVERSE);
arm.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
arm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
Pose2d startPose = new Pose2d(36, -61.5, Math.toRadians(270));
drive.setPoseEstimate(startPose);
TrajectorySequence test = drive.trajectorySequenceBuilder(startPose)
.lineToConstantHeading(new Vector2d(36, -20))
.lineToSplineHeading(new Pose2d(36, -13, Math.toRadians(-45)))
.lineToSplineHeading(new Pose2d(57, -11, 0))
.lineToSplineHeading(new Pose2d(60, -12, 0))
.lineToSplineHeading(new Pose2d(36, -12, 0))
.lineToSplineHeading(new Pose2d(12, -12, 0))
.lineToSplineHeading(new Pose2d(0, -48, Math.toRadians(270)))
.build();
wrist.setPosition(.7);
spooky.setPosition(0.95);
sleep(1000);
claw.setPosition(.82);
sleep(1000);
claw.setPosition(.6);
telemetry.update();
/**
* start of program
*/
waitForStart();
drive.followTrajectorySequence(test);
}
void tagToTelemetry(AprilTagDetection detection)
{
telemetry.addLine(String.format("\nDetected tag ID=%d", detection.id));
telemetry.addLine(String.format("Translation X: %.2f feet", detection.pose.x*FEET_PER_METER));
telemetry.addLine(String.format("Translation Y: %.2f feet", detection.pose.y*FEET_PER_METER));
telemetry.addLine(String.format("Translation Z: %.2f feet", detection.pose.z*FEET_PER_METER));
telemetry.addLine(String.format("Rotation Yaw: %.2f degrees", Math.toDegrees(detection.pose.yaw)));
telemetry.addLine(String.format("Rotation Pitch: %.2f degrees", Math.toDegrees(detection.pose.pitch)));
telemetry.addLine(String.format("Rotation Roll: %.2f degrees", Math.toDegrees(detection.pose.roll)));
}
}