-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathBotbot.java0
248 lines (208 loc) · 9.37 KB
/
Botbot.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
package org.firstinspires.ftc.teamcode;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.hardware.bosch.JustLoggingAccelerationIntegrator;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
import android.graphics.Color;
import org.firstinspires.ftc.robotcore.external.Func;
import org.firstinspires.ftc.robotcore.external.navigation.Acceleration;
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.navigation.Position;
import org.firstinspires.ftc.robotcore.external.navigation.Velocity;
/**
* This is NOT an opmode.
*
* This class is the hardware map of the robot.
*/
public class Botbot {
/* Public OpMode members. */
public DcMotor frontLeft = null;
public DcMotor frontRight = null;
public DcMotor backLeft = null;
public DcMotor backRight = null;
public DcMotor lift = null;
public DcMotor intakeLeft = null;
public DcMotor intakeRight = null;
public CRServo removerOne = null;
public CRServo removerTwo = null;
public Servo stopper = null;
public Servo jewelArm = null;
public BNO055IMU imu;
public Orientation angles;
public Acceleration gravity;
public float dangles[] = new float[3];
ColorSensor colorSense;
double jewelspeed = 0.3;
int jeweltime = 400;
/* local OpMode members. */
HardwareMap hwMap = null;
//private ElapsedTime period = new ElapsedTime();
/* Constructor */
public Botbot(){
}
/* Initialize standard Hardware interfaces */
public void init(HardwareMap ahwMap) {
// Save reference to Hardware map
hwMap = ahwMap;
// Define and Initialize Motors
frontLeft = ahwMap.dcMotor.get("frontLeft");
frontRight = ahwMap.dcMotor.get("frontRight");
backLeft = ahwMap.dcMotor.get("backLeft");
backRight = ahwMap.dcMotor.get("backRight");
lift = ahwMap.dcMotor.get("lift");
intakeLeft = ahwMap.dcMotor.get("intakeLeft");
intakeRight = ahwMap.dcMotor.get("intakeRight");
removerOne = ahwMap.crservo.get("removerOne");
removerTwo = ahwMap.crservo.get("removerTwo");
stopper = ahwMap.servo.get("stopper");
jewelArm = ahwMap.servo.get("jewelArm");
colorSense = ahwMap.get(ColorSensor.class, "sensor_color_distance");
frontLeft.setDirection(DcMotor.Direction.REVERSE);
backLeft.setDirection(DcMotor.Direction.REVERSE);
frontRight.setDirection(DcMotor.Direction.REVERSE);
/*removerOne.setDirection(DcMotor.Direction.REVERSE);
removerTwo.setDirection(DcMotor.Direction.REVERSE);*/
intakeLeft.setDirection(DcMotor.Direction.REVERSE);
// Set all motors to zero power
/*frontLeft.setPower(0);
frontRight.setPower(0);
backLeft.setPower(0);
backRight.setPower(0);*/
// Set all motors to run using encoders.
// May want to use RUN_USING_ENCODERS if encoders are installed.
/*frontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
frontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
backLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
backRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);*/
frontLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
lift.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
intakeLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
intakeRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
lift.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
intakeLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
intakeRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.angleUnit = BNO055IMU.AngleUnit.DEGREES;
parameters.accelUnit = BNO055IMU.AccelUnit.METERS_PERSEC_PERSEC;
parameters.calibrationDataFile = "BNO055IMUCalibration.json"; // see the calibration sample opmode
parameters.loggingEnabled = true;
parameters.loggingTag = "IMU";
parameters.accelerationIntegrationAlgorithm = new JustLoggingAccelerationIntegrator();
imu = ahwMap.get(BNO055IMU.class, "imu");
imu.initialize(parameters);
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.XYZ, AngleUnit.DEGREES);
gravity = imu.getGravity();
dangles[0] = angles.firstAngle;
dangles[1] = angles.secondAngle;
dangles[2] = angles.thirdAngle;
}
public void updateGyro(int damping) {
float origX = angles.firstAngle;
float origY = angles.secondAngle;
float origZ = angles.thirdAngle;
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.XYZ, AngleUnit.DEGREES);
dangles[0] = ((dangles[0] * damping) + angles.firstAngle) / (damping + 1);
dangles[1] = ((dangles[1] * damping) + angles.secondAngle) / (damping + 1);
dangles[2] = ((dangles[2] * damping) + angles.thirdAngle) / (damping + 1);
gravity = imu.getGravity();
}
void setToPosition() {
frontLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
frontRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
backLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
backRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
void driveEncoder(int posL, int posR, double powerL, double powerR, boolean left) {
frontLeft.setTargetPosition(frontLeft.getCurrentPosition() + posL);
frontRight.setTargetPosition(frontRight.getCurrentPosition() + posR);
backLeft.setTargetPosition(backLeft.getCurrentPosition() + posL);
backRight.setTargetPosition(backRight.getCurrentPosition() + posR);
frontLeft.setPower(powerL);
frontRight.setPower(powerR);
backLeft.setPower(powerL);
backRight.setPower(powerR);
if (left) {
while(backLeft.isBusy()) {}
} else {
while(backRight.isBusy()) {}
}
}
void wait(int time) {
try {
Thread.sleep(time);
}
catch(InterruptedException ex) {
Thread.currentThread().interrupt();
}
}
private void setAll(float fl, float fr, float bl, float br) {
frontLeft.setPower(fl);
frontRight.setPower(fr);
backLeft.setPower(bl);
backRight.setPower(br);
}
void driveTime(double l, double r, int time) {
setAll((float) l, (float) r, (float) l, (float) r);
wait(time);
setAll(0, 0, 0, 0);
}
boolean knockJewel(boolean red) {
float hsv[] = {0F, 0F, 0F};
final float values[] = hsv;
int scale = 1;
boolean colorIsRed = false;
jewelArm.setPosition(1);
wait(1000);
Color.RGBToHSV((int) (colorSense.red() * scale),
(int) (colorSense.green() * scale),
(int) (colorSense.blue() * scale),
hsv);
if(hsv[0] < 100 || hsv[0] > 300) colorIsRed = true;
else colorIsRed = false;
if(colorIsRed ^ red) {
driveTime(-jewelspeed, jewelspeed, jeweltime);
jewelArm.setPosition(0.4);
wait(1000);
driveTime(jewelspeed, -jewelspeed, jeweltime);
return(colorIsRed);
} else {
driveTime(jewelspeed, -jewelspeed, jeweltime);
wait(1000);
jewelArm.setPosition(0.4);
driveTime(-jewelspeed, jewelspeed, jeweltime);
return(colorIsRed);
}
}
/***
*
* waitForTick implements a periodic delay. However, this acts like a metronome with a regular
* periodic tick. This is used to compensate for varying processing times for each cycle.
* The function looks at the elapsed cycle time, and sleeps for the remaining time interval.
*
* @param periodMs Length of wait cycle in mSec.
* @throws InterruptedException
*/
/*public void waitForTick(long periodMs) throws InterruptedException {
long remaining = periodMs - (long)period.milliseconds();
// sleep for the remaining portion of the regular cycle period.
if (remaining > 0)
Thread.sleep(remaining);
// Reset the cycle clock for the next pass.
period.reset();
}*/
}