-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathDrive_2_0_fieldCentric.java
567 lines (499 loc) · 24.6 KB
/
Drive_2_0_fieldCentric.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
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.hardware.VoltageSensor;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.Blinker;
import com.qualcomm.robotcore.hardware.HardwareDevice;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.IMU;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.VisionPortal;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
import java.util.List;
// @Disabled
@TeleOp(name = "Drive_2_0_fieldCentric")
public class Drive_2_0_fieldCentric extends LinearOpMode {
// CONSTANTS USED TO ADJUST PROGRAM:
double MAX_DRIVE_MOTOR_POWER = 1.0; // up to 1.0
boolean IS_FIELD_CENTRIC = false;
double MAX_ARM_RAISE_POWER = 0.45;
double MAX_ARM_LOWER_POWER = 0.16;
int MAX_ARM_RAISE_TICKS = 1200;
int MIN_ARM_RAISE_TICKS = 12;
double STICK_DEADZONE = 0.011;
double MAX_ARM_EXTEND_POWER = 0.45;
double MAX_ARM_RETRACT_POWER = 0.45;
int MAX_ARM_EXTEND_TICKS = 2100;
int MIN_ARM_EXTEND_TICKS_WHEN_NOT_PICKING_UP = 120;
int FLIP_TIME_DEBOUNCE_MS = 350;
double CLAW_FLIP_SERVO_NORMAL_POS = 0.19;
double CLAW_FLIP_SERVO_FLIPPED_POS = 0.93;
int GRABBER_TIME_DEBOUNCE_MS = 350;
double GRABBER_SERVO_OPENED_POS = 0.35;
double GRABBER_SERVO_CLOSED_POS = 0.155;
double DRONE_SERVO_LOAD_POS = 0.6;
double DRONE_SERVO_LAUNCH_POS = 0.3;
// An ElapsedTime'r for operations that should wait without pausing the loop
private ElapsedTime currentTime = new ElapsedTime();
// For April Tags
private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera
private AprilTagProcessor aprilTag;
private VisionPortal visionPortal;
private AutoCommon lib;
/**`
* This function is executed when this OpMode is selected from the Driver Station.
*/
boolean resetArm = false;
@Override
public void runOpMode() {
FindPropVisInitData visInitData = new FindPropVisInitData();
lib = new AutoCommon(
hardwareMap,
visInitData);
lib.initAprilTag();
// INIT:
// :find our HW in the hardwareMap:
// IMU:
IMU imu = hardwareMap.get(IMU.class, "imu"); // Retrieve the IMU from the hardware map
imu.initialize(new IMU.Parameters(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.LEFT,RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)));
// Drive Motors:
DcMotor frontright = hardwareMap.get(DcMotor.class, "frontright");
DcMotor rearleft = hardwareMap.get(DcMotor.class, "rearleft");
DcMotor frontleft = hardwareMap.get(DcMotor.class, "frontleft");
DcMotor rearright = hardwareMap.get(DcMotor.class, "rearright");
// Arm extend & arm rotate up/down motors:
DcMotor armextend = hardwareMap.get(DcMotor.class, "armextend");
DcMotor armraise = hardwareMap.get(DcMotor.class, "armrotate");
// Servos for grabbing & flipping (i.e. rotating) the grabber:
Servo flipper = hardwareMap.get(Servo.class, "flipper");
Servo grabber = hardwareMap.get(Servo.class, "grabber");
// Motor for end game lifting of the robot
DcMotor lifter = hardwareMap.get(DcMotor.class, "lifter");
// Motor for launching drone
DcMotor launchMotor = hardwareMap.get(DcMotor.class, "launchMotor");
// Servo for launching drone
Servo droneLauncher = hardwareMap.get(Servo.class, "dronelauncher");
// Arm Limiter Servo
Servo armlimiter = hardwareMap.get(Servo.class, "armlimiter");
// Voltage sensor:
VoltageSensor ControlHub_VoltageSensor = hardwareMap.get(VoltageSensor.class, "Control Hub");
// :set motor directions so that pos/neg tick encoder positions make sense
//frontright.setDirection(DcMotorSimple.Direction.REVERSE);
//rearleft.setDirection(DcMotorSimple.Direction.REVERSE);
lifter.setDirection(DcMotorSimple.Direction.REVERSE);
armraise.setDirection(DcMotorSimple.Direction.REVERSE);
// :reset motor encoder positions to zero
armraise.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
armextend.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lifter.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
// :set initial motor run modes, if not set in the loop
armextend.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
armraise.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
lifter.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
// :config any additional motor parameters
armextend.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
armraise.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
lifter.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
launchMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
// Variables for driver commands
double driverCmd_Fwd, driverCmd_Right, driverCmd_Rotate;
double driverCmd_ArmRaise, driverCmd_ArmExtend;
boolean driverCmd_GrabberToggle, driverCmd_ClawFlipToggle;
double driverCmd_RaiseLifterHooks, driverCmd_LowerLifterHooks;
boolean driverCmd_AutoHoldLifterHooks;
boolean driverCmd_ArmToLowest, driverCmd_GrabTopPixel;
boolean driverCmd_LaunchDrone, driverCmd_LoadDrone;
boolean driverCmd_OverrideArmLim = false;
// Variables for current positions, headings, etc.
int armExtendPositionTicks;
int armRaisePositionTicks;
// Variables for control targets - positions, speeds, headings, etc.
double robotCmd_Fwd, robotCmd_Right, robotCmd_Rotate;
boolean isArmHolding = false; // needs to maintain state, so must be outside loop
int armRaiseTargetPosition = 0; // will set to limit when holding state is entered
boolean isArmExtendHolding = false;
int armExtendTargetPosition = 0; // will set to limit when holding state is entered
boolean isClawInFlippedPosition = false; // false is normal position
int lastTimeFlippedMs = 0; // used to unbounce flipper command
boolean isGrabberInClosedPosition = true; // true is closed
int lastTimeGrabberToggledMs = 0;
boolean lifterUp = false; // false is down
int lastTimeLifted = 0; // used to unbounce lifter command
boolean droneLaunched = false;
int loopsExecuted = 0;
double prevTimeMs = 0.0;
//ElapsedTime currentTime = new ElaspedTime();
// Set flipper to normal position
flipper.setPosition(CLAW_FLIP_SERVO_NORMAL_POS);
// Pull droneLauncher servo back to load drone
droneLauncher.setPosition(DRONE_SERVO_LOAD_POS);
grabber.setPosition(.37);
armraise.setTargetPosition(200); // ?
armextend.setTargetPosition(180);
lib.groundTransitionFlipper();
armraise.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armraise.setPower(0.2);
armextend.setPower(0.15);
lib.avoidArmLimiterFlipper();
sleep(900);
armlimiter.setPosition(.48);
sleep(800);
armextend.setTargetPosition(50);
sleep(500);
armraise.setPower(0.0);
armextend.setPower(0.0);
armraise.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
armextend.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
lib.normalFlipper();
double armLimit = armextend.getCurrentPosition();
telemetry.addLine("Ready for start");
telemetry.update();
waitForStart();
// AFTER START, BEFORE LOOP:
// TODO: minor arm move: raise, extend, lower but keep slightly off ground
while (opModeIsActive()) { // START OF LOOP
double currTimeMs = currentTime.milliseconds();
// DRIVE CONTROLS MAP
// :mechanum drive
driverCmd_Right=Math.pow(gamepad1.right_stick_x, 3);
driverCmd_Fwd=-Math.pow(gamepad1.right_stick_y, 3); // negative because stick_y is up=neg, we want up=pos
driverCmd_Rotate=Math.pow(gamepad1.left_stick_x, 3);
telemetry.addData("driverCmdFwd", driverCmd_Fwd);
// :arm rotate (aka raise/lower) & arm extend
driverCmd_ArmRaise = -gamepad2.left_stick_y;
driverCmd_ArmExtend = -gamepad2.right_stick_y;
driverCmd_ArmToLowest = gamepad2.dpad_down;
driverCmd_GrabTopPixel = gamepad2.dpad_left || gamepad2.dpad_right;
// :claw grab & flip
driverCmd_GrabberToggle = gamepad2.a;
driverCmd_ClawFlipToggle = gamepad2.right_bumper;
// :lifter aka hanger
driverCmd_RaiseLifterHooks = gamepad2.right_trigger;
driverCmd_LowerLifterHooks = gamepad2.left_trigger;
driverCmd_AutoHoldLifterHooks = gamepad2.dpad_down;
driverCmd_LaunchDrone = gamepad1.y && gamepad2.y;
//driverCmd_LoadDrone = gamepad1.x && gamepad2.x;
driverCmd_OverrideArmLim = gamepad1.x;
// CONTROL CODE
// :mechanum drive
double botHeading = imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS); // Get the bot heading from the IMU
telemetry.addData("Robot Heading", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
telemetry.addData("Robot Roll", imu.getRobotYawPitchRollAngles().getRoll(AngleUnit.DEGREES));
telemetry.addData("Robot Pitch", imu.getRobotYawPitchRollAngles().getPitch(AngleUnit.DEGREES));
telemetry.addData("Resetting arm?", resetArm);
if (IS_FIELD_CENTRIC) {
// Rotate the movement direction counter to the bot's rotation
robotCmd_Right = driverCmd_Right * Math.cos(-botHeading) - driverCmd_Fwd * Math.sin(-botHeading);
robotCmd_Fwd = driverCmd_Right * Math.sin(-botHeading) + driverCmd_Fwd * Math.cos(-botHeading);
robotCmd_Rotate = driverCmd_Rotate;
}
else { // normal, robot centric:
robotCmd_Right = driverCmd_Right;
robotCmd_Fwd = driverCmd_Fwd;
robotCmd_Rotate = driverCmd_Rotate;
}
// Denominator is the largest motor power (absolute value) or MAX_DRIVE_MOTOR_POWER
// This ensures all the powers maintain the same ratio,
// but only if at least one is out of the range [-MAX_DRIVE_MOTOR_POWER, MAX_DRIVE_MOTOR_POWER]
double denominator = Math.max(Math.abs(robotCmd_Fwd) + Math.abs(robotCmd_Right) + Math.abs(robotCmd_Rotate), 1.0);
//double frontLeftPower = MAX_DRIVE_MOTOR_POWER * (robotCmd_Fwd - robotCmd_Right + robotCmd_Rotate) / denominator;
//double frontRightPower = MAX_DRIVE_MOTOR_POWER * (robotCmd_Fwd - robotCmd_Right - robotCmd_Rotate) / denominator;
//double backLeftPower = MAX_DRIVE_MOTOR_POWER * (robotCmd_Fwd + robotCmd_Right + robotCmd_Rotate) / denominator;
//double backRightPower = MAX_DRIVE_MOTOR_POWER * (robotCmd_Fwd + robotCmd_Right - robotCmd_Rotate) / denominator;
double frontLeftPower = MAX_DRIVE_MOTOR_POWER * (-robotCmd_Fwd + robotCmd_Right - robotCmd_Rotate) / denominator;
double frontRightPower = MAX_DRIVE_MOTOR_POWER * (-robotCmd_Fwd + robotCmd_Right + robotCmd_Rotate) / denominator;
double backLeftPower = MAX_DRIVE_MOTOR_POWER * (-robotCmd_Fwd - robotCmd_Right - robotCmd_Rotate) / denominator;
double backRightPower = MAX_DRIVE_MOTOR_POWER * (-robotCmd_Fwd - robotCmd_Right + robotCmd_Rotate) / denominator;
// Calculate motor distances by adding/subtracting different inputs
//frontLeftDistance = -fwd_bck + right_left -cw_ccw;
//frontRightDistance = -fwd_bck + right_left + cw_ccw;
//rearLeftDistance = -fwd_bck -right_left -cw_ccw;
//rearRightDistance = -fwd_bck - right_left + cw_ccw;
// Set motor powers
frontleft.setPower(frontLeftPower);
frontright.setPower(frontRightPower);
rearleft.setPower(backLeftPower);
rearright.setPower(backRightPower);
// Raise/Lower Arm (rotate motor) code
armRaisePositionTicks = armraise.getCurrentPosition(); // set to current position of rotate motor
telemetry.addData("Arm Raise Pos:", armRaisePositionTicks);
boolean isArmCmdNone = Math.abs(driverCmd_ArmRaise) <= STICK_DEADZONE;
boolean isArmCmdUp = driverCmd_ArmRaise > STICK_DEADZONE;
boolean isArmCmdDown = driverCmd_ArmRaise < -STICK_DEADZONE;
boolean isArmTooLow = armRaisePositionTicks < MIN_ARM_RAISE_TICKS;
boolean isArmTooHigh = armRaisePositionTicks > MAX_ARM_RAISE_TICKS;
boolean isArmNearHighLimit = armRaisePositionTicks > (MAX_ARM_RAISE_TICKS - 25);
if (!driverCmd_OverrideArmLim) {
if (resetArm) {
armraise.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
resetArm = false;
armraise.setMode(DcMotor.RunMode.RUN_USING_ENCODERS);
}
if (isArmCmdNone) { // hold within limits
if (!isArmHolding) { // entering hold state
// without this block, we keep updating the
// target position = to the current position,
// causing the hold to drift due to gravity & bouncing
isArmHolding = true;
armRaiseTargetPosition = armRaisePositionTicks;
if (isArmTooLow) {
armRaiseTargetPosition = 82;
} else if (isArmTooHigh) {
armRaiseTargetPosition = MAX_ARM_RAISE_TICKS;
}
armraise.setTargetPosition(armRaiseTargetPosition);
armraise.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armraise.setPower(0.265);
} else {
armraise.setTargetPosition(armRaiseTargetPosition);
armraise.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armraise.setPower(0.265);
}
} else if (isArmCmdUp) {
isArmHolding = false;
if ((isArmTooHigh || isArmNearHighLimit)) {
armraise.setTargetPosition(MAX_ARM_RAISE_TICKS);
armraise.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armraise.setPower(0.265);
} else {
armraise.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
if (armRaisePositionTicks > 683.55) {
armraise.setPower(0.33 * driverCmd_ArmRaise * MAX_ARM_RAISE_POWER);
} else {
armraise.setPower(driverCmd_ArmRaise * MAX_ARM_RAISE_POWER);
}
}
} else { // isArmCmdDown
isArmHolding = false;
if (isArmTooLow) {
armraise.setTargetPosition(82);
armraise.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armraise.setPower(0.265);
} else {
armraise.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
armraise.setPower(driverCmd_ArmRaise * MAX_ARM_LOWER_POWER);
}
}
} else {
armraise.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODERS);
armraise.setPower(driverCmd_ArmRaise);
resetArm = true;
}
// Extend Arm code
armExtendPositionTicks = armextend.getCurrentPosition();
boolean isArmCmdExtendNone = Math.abs(driverCmd_ArmExtend) <= STICK_DEADZONE;
boolean isArmCmdExtend = driverCmd_ArmExtend > STICK_DEADZONE;
boolean isArmCmdRetract = driverCmd_ArmExtend < -STICK_DEADZONE;
boolean isArmTooRetracted = armExtendPositionTicks < MIN_ARM_EXTEND_TICKS_WHEN_NOT_PICKING_UP;
boolean isArmTooExtended = armExtendPositionTicks > MAX_ARM_EXTEND_TICKS;
boolean isArmNearRetractLimit = armExtendPositionTicks < (MIN_ARM_EXTEND_TICKS_WHEN_NOT_PICKING_UP + 25);
boolean isArmNearExtendLimit = armExtendPositionTicks > (MAX_ARM_EXTEND_TICKS - 25);
// run arm to set positions using buttons
// dPadDown -> ground, dPadLeft/right -> second stacked pixel
// a grabs/ lets go of pixel
if (driverCmd_ArmToLowest) { // send the arm all the way to the ground
armExtendTargetPosition = 675;
armextend.setTargetPosition(armExtendTargetPosition);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setPower(0.265);
telemetry.addLine("Sending arm to lowest");
}
if (driverCmd_GrabTopPixel) { // grab top pixel in stack of two
armExtendTargetPosition = 455;
armextend.setTargetPosition(armExtendTargetPosition);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setPower(0.265);
telemetry.addLine("Sending arm to grab top pixel");
}
if (isArmCmdExtendNone) { // hold within limits
telemetry.addData("extend:","holding");
if (!isArmExtendHolding) { // entering hold state
// without this block, we keep updating the
// target position = to the current position,
// causing the hold to drift due to gravity & bouncing
isArmExtendHolding = true;
if (isArmTooRetracted) {
armExtendTargetPosition = MIN_ARM_EXTEND_TICKS_WHEN_NOT_PICKING_UP;
}
else if (isArmTooExtended) {
armExtendTargetPosition = MAX_ARM_EXTEND_TICKS;
}
else {
armExtendTargetPosition = armExtendPositionTicks; // as we enter Holding state, set Target to Current position this one time
}
}
else {
armextend.setTargetPosition(armExtendTargetPosition);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setPower(0.265);
}
}
else if (isArmCmdExtend) {
telemetry.addData("extend:","extending");
isArmExtendHolding = false;
if (isArmTooExtended || isArmNearExtendLimit) {
armextend.setTargetPosition(MAX_ARM_EXTEND_TICKS);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setPower(0.265);
}
else {
armextend.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
armextend.setPower(driverCmd_ArmExtend * MAX_ARM_EXTEND_POWER);
}
}
else if (isArmCmdRetract) { // isArmCmdRetract
telemetry.addData("extend:","retracting");
isArmExtendHolding = false;
if (isArmTooRetracted || isArmNearRetractLimit) {
armextend.setTargetPosition(MIN_ARM_EXTEND_TICKS_WHEN_NOT_PICKING_UP);
armextend.setMode(DcMotor.RunMode.RUN_TO_POSITION);
armextend.setPower(0.265);
}
else {
armextend.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
armextend.setPower(driverCmd_ArmExtend * MAX_ARM_RETRACT_POWER);
}
}
telemetry.addData("Arm Extend Pos:", armExtendPositionTicks);
// Claw Flip / Rotater:
boolean isFlipDebounceTimeElapsed = ((int) currentTime.milliseconds() - lastTimeFlippedMs)
> FLIP_TIME_DEBOUNCE_MS;
/*
if (driverCmd_ClawFlipToggle && isFlipDebounceTimeElapsed) {
if (isClawInFlippedPosition) { // set to default position
isClawInFlippedPosition = false;
//flipper.setPosition(CLAW_FLIP_SERVO_NORMAL_POS);
lib.normalFlipper();
}
else { // rotate to 180 degrees
isClawInFlippedPosition = true;
//flipper.setPosition(CLAW_FLIP_SERVO_FLIPPED_POS);
lib.reverseFlipper();
}
lastTimeFlippedMs = (int) currentTime.milliseconds(); // refresh 'lastTime', regardless of which direction we went
}
*/
if (driverCmd_ClawFlipToggle && isFlipDebounceTimeElapsed) {
lastTimeFlippedMs = (int) currentTime.milliseconds(); // refresh 'lastTime', regardless of which direction we went
if (isClawInFlippedPosition) {
isClawInFlippedPosition = false;
} else {
isClawInFlippedPosition = true;
}
}
if (isClawInFlippedPosition) {
lib.reverseFlipper();
} else {
lib.normalFlipper();
}
// grabber servo code
boolean isGrabberDebounceTimeElapse = ((int) currentTime.milliseconds() - lastTimeGrabberToggledMs)
> GRABBER_TIME_DEBOUNCE_MS;
if (driverCmd_GrabberToggle && isGrabberDebounceTimeElapse)
{
if (isGrabberInClosedPosition){
isGrabberInClosedPosition = false;
grabber.setPosition(GRABBER_SERVO_OPENED_POS); // open
} else {
isGrabberInClosedPosition = true;
grabber.setPosition(GRABBER_SERVO_CLOSED_POS);
}
lastTimeGrabberToggledMs = (int) currentTime.milliseconds(); // refresh 'lastTime', regardless of which direction we went
}
// LIFTER (aka robot HANGING)
lifter.setPower(driverCmd_RaiseLifterHooks - driverCmd_LowerLifterHooks);
telemetry.addData("lifter pos:", lifter.getCurrentPosition());
// Drone launch control: both driver 1 and 2 must push Dpad up, and must be 90 sec into match
//if (driverCmd_LoadDrone) {
// droneLauncher.setPosition(DRONE_SERVO_LOAD_POS);
//}
// Drone launch control: both driver 1 and 2 must push Dpad up, and must be 90 sec into match
if (true) {
telemetry.addLine("--------------------");
if (driverCmd_LaunchDrone && !droneLaunched) {
droneLaunched = true;
telemetry.addLine("Launching drone...");
AprilTagDetection look43 = lib.getAprilTagDetection(3);
AprilTagDetection look44 = lib.getAprilTagDetection(4);
if (look43 != null) {
telemetry.addLine("found tag 3...");
telemetry.update();
double yDistance = look43.ftcPose.y;
lib.drive(12 - yDistance, 0, 0, 0);
//double zRotation = imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES);
//lib.drive(0, 0, 90 + zRotation, 0);
frontleft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontright.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rearleft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rearright.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
} else if (look44 != null) {
telemetry.addLine("found tag 4...");
telemetry.update();
//sleep(2500);
double yDistance = look44.ftcPose.y;
lib.drive(12 - yDistance, 0, 0, 0);
//double imuYaw = imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES);
//if (imuYaw != 0.0) {
// lib.drive(0, 0, imuYaw - 90, 0);
//}
} else {
telemetry.addLine("no tags found...");
telemetry.addLine("Hopefully you lined it up right");
telemetry.update();
//sleep(2500);
}
double batt = 13.123;
double adjVel = 2450.123;
batt = ControlHub_VoltageSensor.getVoltage();
double baseVelocity = 2450;
adjVel = (12.9 / batt + 1.0) / 2.0 * baseVelocity;
((DcMotorEx)launchMotor).setVelocity(adjVel); // 2450 2300 3500
sleep(200); // 270
//droneVelAct = ((DcMotorEx)launchMotor).getVelocity(); // .getVelocity(AngleUnit.DEGREES);
((DcMotorEx)launchMotor).setVelocity(0);
telemetry.update();
launchMotor.setPower(0);
frontleft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontright.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rearleft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rearright.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
} else {
if (!droneLaunched) {
telemetry.addLine("Ready to launch drone");
} else {
telemetry.addLine("Drone away");
}
}
telemetry.addLine("---------------------");
} else {
telemetry.addData("Time until ready to launch", ((int) 90 - (currTimeMs/1000)));
}
if (driverCmd_OverrideArmLim) {
armraise.setPower(gamepad2.left_stick_y * -0.4);
armraise.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
telemetry.addLine("Overriding arm");
}
telemetry.addData("DriverCmd_ToLowest", driverCmd_ArmToLowest);
telemetry.addData("DriverCmd_GrabTopPixel", driverCmd_GrabTopPixel);
telemetry.addData("armraise target position", armraise.getTargetPosition());
telemetry.addData("armextend target position", armextend.getTargetPosition());
telemetry.addData("Override commanded", driverCmd_OverrideArmLim);
loopsExecuted ++;
telemetry.addData("loops:", loopsExecuted);
telemetry.addData("time delta (ms):", currTimeMs - prevTimeMs);
telemetry.addData("time:", currTimeMs / 1000.0);
prevTimeMs = currTimeMs;
telemetry.update();
} // END OF WHILE LOOP
} // END OF RUN OPMODE FUNCTION
} // END OF CLASS DEF