-
Notifications
You must be signed in to change notification settings - Fork 1
/
Robot.java
322 lines (261 loc) · 10.7 KB
/
Robot.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
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
package org.firstinspires.ftc.teamcode;
import static android.os.SystemClock.currentThreadTimeMillis;
import static android.os.SystemClock.sleep;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.Telemetry;
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.Orientation;
import org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.*;
public class Robot {
/* Public OpMode members. */
DcMotor fl = null;
DcMotor fr = null;
DcMotor bl = null;
DcMotor br = null;
DcMotor lift = null;
DcMotor duck = null;
CRServo crServo = null;
Servo clawServo = null;
double CIRCUMFERENCEOFWHEEL = 314.159; //mm
double ENCODERTICKS = 537.7;
double GEARRATIO = 1;
double TICKSTOMMTRAVEL = (CIRCUMFERENCEOFWHEEL/ENCODERTICKS) * GEARRATIO;
HardwareMap hwMap = null;
Orientation angles;
BNO055IMU imu;
Telemetry telemetry;
public void init(HardwareMap ahwMap, Telemetry tele) { //pass in hardwaremap and telemetry in the code to init stuff
hwMap = ahwMap;
telemetry = tele;
fl = hwMap.dcMotor.get("front_left_motor");
fr = hwMap.dcMotor.get("front_right_motor");
bl = hwMap.dcMotor.get("back_left_motor");
br = hwMap.dcMotor.get("back_right_motor");
lift = hwMap.dcMotor.get("lift_dcMotor");
duck = hwMap.dcMotor.get("duck_motor");
fl.setDirection(DcMotorSimple.Direction.REVERSE);
bl.setDirection(DcMotorSimple.Direction.REVERSE);
//fr.setDirection(DcMotorSimple.Direction.REVERSE);
//br.setDirection(DcMotorSimple.Direction.REVERSE);
clawServo = hwMap.servo.get("clawServo");
//liftServo = hwMap.crservo.get("liftServo");
imu = hwMap.get(BNO055IMU.class, "imu");
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.accelUnit = BNO055IMU.AccelUnit.METERS_PERSEC_PERSEC;
parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS;
imu.initialize(parameters);
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.RADIANS);
}
public int tickToMM(double mm){
return (int) (mm/TICKSTOMMTRAVEL);
}
public void driveForwardDistance(double power, int distance){
fl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fr.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
bl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
br.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fl.setTargetPosition(distance);
fr.setTargetPosition(distance);
bl.setTargetPosition(distance);
br.setTargetPosition(distance);
fl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
fr.setMode(DcMotor.RunMode.RUN_TO_POSITION);
bl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
br.setMode(DcMotor.RunMode.RUN_TO_POSITION);
driveForward(power);
while(fl.isBusy() && fr.isBusy() && bl.isBusy() && br.isBusy()) {
}
stopDriving();
fl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fr.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
bl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
br.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
public void driveBackDistance(double power, int distance){
fl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fr.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
bl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
br.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fl.setTargetPosition(-distance);
fr.setTargetPosition(-distance);
bl.setTargetPosition(-distance);
br.setTargetPosition(-distance);
fl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
fr.setMode(DcMotor.RunMode.RUN_TO_POSITION);
bl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
br.setMode(DcMotor.RunMode.RUN_TO_POSITION);
driveBack(power);
while(fl.isBusy() && fr.isBusy() && bl.isBusy() && br.isBusy())
{
}
stopDriving();
fl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fr.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
bl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
br.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
public void driveRightDistance(double power, int distance){
fl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fr.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
bl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
br.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fl.setTargetPosition(distance);
fr.setTargetPosition(-distance);
bl.setTargetPosition(-distance);
br.setTargetPosition(distance);
fl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
fr.setMode(DcMotor.RunMode.RUN_TO_POSITION);
bl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
br.setMode(DcMotor.RunMode.RUN_TO_POSITION);
driveRight(power);
while(fl.isBusy() && fr.isBusy() && bl.isBusy() && br.isBusy())
{
}
stopDriving();
fl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fr.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
bl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
br.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
public void driveLeftDistance(double power, int distance){
fl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fr.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
bl.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
br.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
fl.setTargetPosition(-distance);
fr.setTargetPosition(distance);
bl.setTargetPosition(distance);
br.setTargetPosition(-distance);
fl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
fr.setMode(DcMotor.RunMode.RUN_TO_POSITION);
bl.setMode(DcMotor.RunMode.RUN_TO_POSITION);
br.setMode(DcMotor.RunMode.RUN_TO_POSITION);
driveLeft(power);
while(fl.isBusy() && fr.isBusy() && bl.isBusy() && br.isBusy())
{
}
stopDriving();
fl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fr.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
bl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
br.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
public void driveForward(double power) {
fl.setPower(power);
fr.setPower(power);
bl.setPower(power);
br.setPower(power);
}
private void driveBack(double power){
fl.setPower(-power);
fr.setPower(-power);
bl.setPower(-power);
br.setPower(-power);
}
private void driveRight(double power){
fl.setPower(power);
fr.setPower(-power);
bl.setPower(-power);
br.setPower(power);
}
private void driveLeft(double power){
fl.setPower(-power);
fr.setPower(power);
bl.setPower(power);
br.setPower(-power);
}
private void stopDriving() {
fl.setPower(0);
fr.setPower(0);
bl.setPower(0);
br.setPower(0);
}
public void duckMotor(double power, int time){ //might not work look at sleep line
duck.setPower(power);
sleep(time);
duck.setPower(0);
}
public void rotate(double wantedAngle){
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
double startTime = System.nanoTime();
double target = 0;
target = wantedAngle;
double angle = 0;
int totalTime = 0;
double error = 90, P, I, D, integral = 0, derivative, correction, t, lastTime = 0, dt = 0.1, lastError = 90;
double kp = .0135;
double ki = 0;
double kd = .02;
while(Math.abs(error) > 1){
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
angle = angles.firstAngle;
t = (double)System.nanoTime()/10;
if (lastTime != 0){
dt = t - lastTime;
}
error = target - angle;
integral = ki * ((error - lastError) * dt);
derivative = kd * ((error - lastError) / dt);
P = kp * error;
I = ki * integral;
D = kd * derivative;
correction = P + I + D;
fl.setPower(-correction);
fr.setPower(correction);
bl.setPower(-correction);
br.setPower(correction);
//System.out.println(P + " " + I + " " + D);
System.out.println(error);
System.out.println(angles);
telemetry.addData("Dt", dt);
telemetry.addData("Error", error);
telemetry.addData("correction:", correction);
telemetry.addData("top Left Power", fl.getPower());
telemetry.addData("top Right Power", fr.getPower());
telemetry.addData("bottom Left Power", bl.getPower());
telemetry.addData("bottom Right Power", br.getPower());
telemetry.addData("Angle", angle);
telemetry.update();
lastError = error;
lastTime = t;
totalTime += t;
}
telemetry.addData("Angle", angle);
telemetry.addData("totalTime: ", totalTime * 10E-9);
telemetry.update();
System.out.println("angle: " + angle);
System.out.println("totalTime: " + (totalTime * 10E-9));
fl.setPower(0);
fr.setPower(0);
bl.setPower(0);
br.setPower(0);
}
public void liftMotor(int ticks, double power){
lift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lift.setTargetPosition(ticks);
lift.setMode(DcMotor.RunMode.RUN_TO_POSITION);
lift.setPower(power);
while(lift.isBusy()){
}
lift.setPower(0);
lift.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
public void clawOpen(){
double ninja = .7; //ninja from -180 to +180
clawServo.setPosition(ninja);
}
public void clawClamp(){
double pirateos = .375; //-180 to +180
clawServo.setPosition(pirateos);
}
}