forked from FIRST-Tech-Challenge/FtcRobotController
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathSuperStructure.java
More file actions
153 lines (131 loc) · 5 KB
/
SuperStructure.java
File metadata and controls
153 lines (131 loc) · 5 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
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
package org.firstinspires.ftc.teamcode;
import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
@Config
public class SuperStructure {
public enum ReleaseLifter{
BACK,FRONT
}
public static int LIFT_MIN = 0;
public static int LIFT_LOW_Low = 1877;
public static int LIFT_MID_Low = 2988;
public static int LIFT_HIGH_Low = 2634;
public static int LIFT_LOW_High = 3726;
public static int LIFT_MID_High = 3200;
public static int LIFT_HIGH_High = 4164;
public static final int LIFT_TOLERANCE = 20;
public static final double backDoor_close = 0.75,backDoor_middle = 0.5, backDoor_open = 0;
private final DcMotorEx strafeDrive,frontLift,backLift;
private final Servo strafe,backDoor,frontDoorLeft,frontDoorRight;
private Runnable drive_period;
private final LinearOpMode opMode;
private int liftLocation;
public SuperStructure(LinearOpMode opMode) {
this.opMode = opMode;
HardwareMap hardwareMap = opMode.hardwareMap;
liftLocation = 0;
strafeDrive = hardwareMap.get(DcMotorEx.class,"strafe_drive");
frontLift = hardwareMap.get(DcMotorEx.class, "frontSlide");
backLift = hardwareMap.get(DcMotorEx.class,"backSlide");
frontLift.setDirection(DcMotorSimple.Direction.FORWARD);
backLift.setDirection(DcMotorSimple.Direction.REVERSE);
frontLift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontLift.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backLift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backLift.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
strafe = hardwareMap.get(Servo.class,"strafe");
backDoor = hardwareMap.get(Servo.class,"doorBack");
frontDoorLeft = hardwareMap.get(Servo.class,"doorLeft");
frontDoorRight = hardwareMap.get(Servo.class,"doorRight");
}
public void toOriginal() {
liftLocation = 0;
setFrontLiftPosition(LIFT_MIN, 1);
setBackLiftPosition(LIFT_MIN,1);
}
public void runtimeResetLifter() {
setLifterPower(-0.2);
sleep_with_drive(200);
setLifterPower(0);
sleep_with_drive(50);
setLifterPower(0);
frontLift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backLift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
setFrontLiftPosition(0,1);
setBackLiftPosition(0,1);
}
public void toLowRelease(ReleaseLifter releaseLifter) {
liftLocation = 1;
switch (releaseLifter){
case BACK:
setBackLiftPosition(LIFT_LOW_Low,1);
setFrontLiftPosition(LIFT_LOW_High,1);
return;
case FRONT:
setFrontLiftPosition(LIFT_LOW_Low,1);
setBackLiftPosition(LIFT_LOW_High,1);
}
}
public void toMidRelease(ReleaseLifter releaseLifter) {
liftLocation = 2;
switch (releaseLifter){
case BACK:
setBackLiftPosition(LIFT_MID_Low,1);
setFrontLiftPosition(LIFT_MID_High,1);
return;
case FRONT:
setFrontLiftPosition(LIFT_MID_Low,1);
setBackLiftPosition(LIFT_MID_High,1);
}
}
public void toHighRelease(ReleaseLifter releaseLifter) {
liftLocation = 3;
switch (releaseLifter){
case BACK:
setBackLiftPosition(LIFT_HIGH_Low,1);
setFrontLiftPosition(LIFT_HIGH_High,1);
return;
case FRONT:
setFrontLiftPosition(LIFT_HIGH_Low,1);
setBackLiftPosition(LIFT_HIGH_High,1);
}
}
private void setFrontLiftPosition(int pos,double power){
frontLift.setTargetPosition(pos);
frontLift.setMode(DcMotor.RunMode.RUN_TO_POSITION);
frontLift.setPower(power);
}
private void setBackLiftPosition(int pos,double power){
backLift.setTargetPosition(pos);
backLift.setMode(DcMotor.RunMode.RUN_TO_POSITION);
backLift.setPower(power);
}
private void setLifterPower(double power) {
frontLift.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backLift.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontLift.setPower(power);
backLift.setPower(power);
drive_period.run();
frontLift.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backLift.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontLift.setPower(power);
backLift.setPower(power);
}
public double getFrontLifterPos() {
return (double) frontLift.getCurrentPosition();
}
public double getBackLifterPos() {
return (double) backLift.getCurrentPosition();
}
public void sleep_with_drive(double time_mm) {
long start_time = System.currentTimeMillis();
while (opMode.opModeIsActive() && System.currentTimeMillis() - start_time < time_mm) {
drive_period.run();
}
}
}