-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathServi.java0
284 lines (245 loc) · 9.83 KB
/
Servi.java0
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
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.util.Range;
/*
### OUTLINE OF CONCEPT ###
#Originals
x = joyx
y = joyy
wheels = [angle1, angle2, angle3, ...]
#To polar coordinates
r = min(sqrt(x*x + y*y), 1)
theta = atan2(x, y)
#Counter for gyroscope
theta += gyro
#Wheel power
for angle in wheels:
#closeness to front: sin()
power = cos(theta + angle)
*/
@TeleOp(name="Servi", group="ser")
public class Servi extends OpMode {
/* Declare OpMode members. */
private ServiHardware robot = new ServiHardware();
// Defines wheel positions
double[] wheels = new double[]{ 0,((double)1/2)*3.1415,(double)3.1415,((double)3/2)*3.1415 };
// Array for motor powers
double[] powers = new double[]{ 0,0,0,0 };
// Current angle of gyroscope
float currentAngle = 0;
// Field centric drive; toggled with X
boolean fieldcentric = true;
// Relative zero for field-centric drive
float zero = 0;
// Self-righting; disables manual turning; toggles with Y
boolean righteous = false;
// Currently turning; used for exact turns
boolean turning = false;
// Speed multiplier from 1-10(11); adjusted up/down with A/B
int speed = 10;
// For detecting presses of X
boolean fcswitch = false;
// For detecting presses of Y
boolean rgswitch = false;
// For detecting presses of B
boolean slswitch = false;
// For detecting presses of A
boolean fsswitch = false;
// For detecting presses of back
boolean lsbswitch = false;
// For detecting presses of start
boolean rsbswitch = false;
// Initialize variables
double x,y,turn,r,theta,setangle,delta;
/*
* Code to run ONCE when the driver hits INIT
*/
@Override
public void init() {
/* Initialize the hardware variables.
* The init() method of the hardware class does all the work here
*/
robot.init(hardwareMap);
telemetry.addData("Robot", "ready");
}
/*
* Code to run REPEATEDLY after the driver hits INIT, but before they hit PLAY
*/
@Override
public void init_loop() {
}
/*
* Code to run ONCE when the driver hits PLAY
*/
@Override
public void start() {
}
/*
* Code to run REPEATEDLY after the driver hits PLAY but before they hit STOP
*/
@Override
public void loop() {
robot.updateGyro(5); // Obtain new gyro information
currentAngle = robot.angles.thirdAngle;
// --- GAMEPAD INPUT ---
turn = gamepad1.right_stick_x; // Use the right joy x for turning
y = gamepad1.left_stick_y; // Get left joy y
x = -gamepad1.left_stick_x; // Get left joy x
// --- TO POLAR COORDINATES ---
r = Math.min(Math.sqrt(x*x + y*y), 1); // Convert x,y to speed
theta = Math.atan2(x, y); // and direction
// --- DRIVE MODES ---
if(speed == 11 && r != 0.0) {
r = 1.0;
}
if(fieldcentric) { // If field-centric:
theta += Math.toRadians(currentAngle - zero); // Compensate direction for gyro
}
if(righteous || turning) { // If self-righting or turning:
if(turn == 0.0) { // If not manually turning:
delta = currentAngle - setangle; // Get needed correction
turn = wrap(delta) / 180; // Set turn to correction
}
else { // If manually turning:
setangle = currentAngle; // Set return angle
}
if(Math.abs(turn) < 0.05) turn = 0; // don't bother if you're super close
if(turn < 0.15 && turn > 0.05) turn = 0.15; // if .05-.15, use .15 power
if(turn > -0.15 && turn < -0.05) turn = -0.15; // ditto for negative; avoids squeeking
}
if(turning && turn == 0) { // If it was turning and finished:
turning = false; // Stop turning
}
// --- WHEEL POWERS ---
r = r*r*r; // Curve the speed exponentially
r = r * speed/10.0; // Adjust the translation speed
for(int i = 0; i != wheels.length; i++) { // For all the wheels:
powers[i] = (Math.sin(wheels[i] - theta) * r ) - turn; // calculate the desired speed
// sin(wheel direction - desired direction finds speed), *r accounts
// for joystick speed, +turn adds in turning with joystick/self
}
robot.one.setPower(powers[0]); // Set motor powers
robot.two.setPower(powers[1]); // si(x, 1.5) applies curve, *(speed/10) applies speed
robot.three.setPower(powers[2]); // Range.clip() applies limit
robot.four.setPower(powers[3]);
// --- DRIVE MODE CONTROLS ---
if(gamepad1.start) { // If "shift" is held and X is pushed:
zero = currentAngle; // Reset forwards for field-centric
}
else if(!fcswitch && gamepad1.x) { // Otherwise, if X is pushed:
fieldcentric = !fieldcentric; // Toggle field-centric
}
if(!rgswitch && gamepad1.y) { // If Y is pushed:
righteous = !righteous; // Toggle self-righting
setangle = currentAngle; // Set return angle
}
if(!slswitch && gamepad1.b && speed > 1) { // If B is pushed and speed over 1:
speed -= 1; // decrease speed
}
if(!fsswitch && gamepad1.a && speed < 10) { // If A is pushed and speed under 10:
speed += 1; // increase speed
}
if(!fsswitch && gamepad1.b && gamepad1.a && speed == 10) {
speed = 11;
}
if(!lsbswitch && gamepad1.left_stick_button) { // If back is pressed:
setangle = wrap(currentAngle + 84); // Set desired angle to current +90
turning = true; // Set to turning
}
if(!rsbswitch && gamepad1.right_stick_button) { // If start is pressed:
setangle = wrap(currentAngle - 84); // Set desired angle to current -90
turning = true; // Set to turning
}
fcswitch = gamepad1.x; // Store button states for next round
rgswitch = gamepad1.y;
slswitch = gamepad1.b;
fsswitch = gamepad1.a;
lsbswitch = gamepad1.left_stick_button;
rsbswitch = gamepad1.right_stick_button;
// --- TELEMETRY ---
telemetry.addData("fieldcentric (X to toggle)", fieldcentric);
telemetry.addData("righteous (Y to toggle)", righteous);
telemetry.addData("speed (A/B +/-)", speed);
telemetry.addData("", null);
telemetry.addData("r", r);
telemetry.addData("theta", theta);
for(int i = 0; i != wheels.length; i++) {
telemetry.addData("wheel " + Integer.toString(i + 1), powers[i]);
}
if(fieldcentric || righteous || turning) {
telemetry.addData("", null);
telemetry.addData("angle", currentAngle);
}
if(fieldcentric) {
telemetry.addData("zero", zero);
}
if(righteous || turning) {
telemetry.addData("delta", delta);
telemetry.addData("delta%180", delta%180);
telemetry.addData("turn", turn*180);
}
// Lift and latch
if(gamepad2.dpad_up) {
robot.lift.setPower(-1);
}
else if(gamepad2.dpad_down) {
robot.lift.setPower(1);
}
else {
robot.lift.setPower(0);
}
if(gamepad2.dpad_left) {
robot.latch.setPower(-1);
}
else if(gamepad2.dpad_right) {
robot.latch.setPower(1);
}
else {
robot.latch.setPower(0);
}
if(gamepad1.left_bumper) {
robot.grab.setPower(1);
} else if(gamepad1.right_bumper) {
robot.grab.setPower(-1);
} else {
robot.grab.setPower(0);
}
/*if(gamepad1.right_trigger > 0) {
robot.arm.setPower(gamepad1.right_trigger * 0.75);
} else if(gamepad1.left_trigger > 0) {
robot.arm.setPower(gamepad1.left_trigger * -0.75);
} else {
robot.arm.setPower(0);
}
if(gamepad1.x) {
robot.spool.setPower(1);
} else if(gamepad1.y) {
robot.spool.setPower(-1);
} else {
robot.spool.setPower(0);
}*/ //we're already using x and y for driving modes and it's better to use the other gamepad for auxilary functions anyway
robot.arm.setPower(gamepad2.left_stick_y); //
robot.spool.setPower(gamepad2.right_stick_y);
//robot.grab.setPower(gamepad1.left_trigger - gamepad1.right_trigger);
updateTelemetry(telemetry);
}
/*
* Code to run ONCE after the driver hits STOP
*/
@Override
public void stop() {
}
private double wrap(double input) {
while(Math.abs(input) > 180) {
if(input < -180) {
input += 360;
}
else {
input -= 360;
}
}
return input;
}
}