-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathAutonomousRedOdometer.java
More file actions
185 lines (160 loc) · 8.87 KB
/
AutonomousRedOdometer.java
File metadata and controls
185 lines (160 loc) · 8.87 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
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
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;
import java.io.File; // Import the File class
import java.io.FileNotFoundException; // Import this class to handle errors
import java.util.Scanner; // Import the Scanner class to read text files
import org.json.JSONException;
import org.json.JSONObject;
import org.json.JSONArray;
@Autonomous(name="RedOdometer DON'T USE", group="Pushbot")
public class AutonomousRedOdometer extends LinearOpMode {
private DcMotor leftBack = null;
private DcMotor rightBack = null;
private DcMotor leftFront = null;
private DcMotor rightFront = null;
private DcMotor arm = null;
private Servo hand = null;
private DcMotor wheel = null;
private ElapsedTime runtime = new ElapsedTime();
public void setPowers(double direction, double speed, double rotation){
double leftBackPower;
double rightBackPower;
double leftFrontPower;
double rightFrontPower;
double forward = Math.cos(direction)*speed;
double side = Math.sin(direction)*speed;
rightBackPower = Range.clip((forward + side + rotation), -1.0, 1.0);
leftBackPower = Range.clip((forward - side - rotation), -1.0, 1.0);
rightFrontPower = Range.clip((forward - side + rotation), -1.0, 1.0);
leftFrontPower = Range.clip((forward + side - rotation), -1.0, 1.0);
leftBack.setPower(leftBackPower);
rightBack.setPower(rightBackPower);
leftFront.setPower(leftFrontPower);
rightFront.setPower(rightFrontPower);
}
private void waitOneSecond() {
sleep(1000);
}
@Override
public void runOpMode() {
// ArrayList<double[]> Instructions = new ArrayList<double[]>();
// double instruction1[] = {1, 2, 3};
// Instructions.add(instruction1);
leftBack = hardwareMap.get(DcMotor.class, "left_back");
rightBack = hardwareMap.get(DcMotor.class, "right_back");
leftFront = hardwareMap.get(DcMotor.class, "left_front");
rightFront = hardwareMap.get(DcMotor.class, "right_front");
arm = hardwareMap.get(DcMotor.class, "arm");
hand = hardwareMap.get(Servo.class, "hand");
wheel = hardwareMap.get(DcMotor.class, "wheel");
leftBack.setDirection(DcMotor.Direction.FORWARD);
rightBack.setDirection(DcMotor.Direction.REVERSE);
leftFront.setDirection(DcMotor.Direction.FORWARD);
rightFront.setDirection(DcMotor.Direction.REVERSE);
wheel.setDirection(DcMotor.Direction.FORWARD);
runtime.reset();
waitForStart();
double startTime = getRuntime();
double loops = 0;
double xAmt = 0;//(Math.random() - 0.5)/2;
double yAmt = -0.25;//(Math.random() - 0.5)/2;
double leftFrontPower = yAmt + xAmt;
double rightFrontPower = yAmt - xAmt;
double leftBackPower = yAmt - xAmt;
double rightBackPower = yAmt + xAmt;
int leftFrontPreMovePosition = leftFront.getCurrentPosition();
int rightFrontPreMovePosition = rightFront.getCurrentPosition();
int leftBackPreMovePosition = leftBack.getCurrentPosition();
int rightBackPreMovePosition = rightBack.getCurrentPosition();
int leftFrontInitPosition = leftFront.getCurrentPosition();
int rightFrontInitPosition = rightFront.getCurrentPosition();
int leftBackInitPosition = leftBack.getCurrentPosition();
int rightBackInitPosition = rightBack.getCurrentPosition();
double leftFrontMultiplier = 1;
double rightFrontMultiplier = 1;
double leftBackMultiplier = 1;
double rightBackMultiplier = 1;
while(opModeIsActive()) {
double time = getRuntime() + 1;
while(getRuntime() < time){
telemetry.clear();
double xPos = leftFront.getCurrentPosition() - leftFrontInitPosition + rightBack.getCurrentPosition() - rightBackInitPosition - rightFront.getCurrentPosition() + rightFrontInitPosition - leftBack.getCurrentPosition() + leftBackInitPosition;
double yPos = leftFront.getCurrentPosition() - leftFrontInitPosition + rightBack.getCurrentPosition() - rightBackInitPosition + rightFront.getCurrentPosition() - rightFrontInitPosition + leftBack.getCurrentPosition() - leftBackInitPosition;
if(xPos > 1000){
xAmt = Math.abs(xAmt);
leftFrontPreMovePosition = leftFront.getCurrentPosition();
rightFrontPreMovePosition = rightFront.getCurrentPosition();
leftBackPreMovePosition = leftFront.getCurrentPosition();
rightBackPreMovePosition = rightFront.getCurrentPosition();
leftFrontPower = yAmt + xAmt;
rightFrontPower = yAmt - xAmt;
leftBackPower = yAmt - xAmt;
rightBackPower = yAmt + xAmt;
}
if(xPos < -1000){
xAmt = -Math.abs(xAmt);
leftFrontPreMovePosition = leftFront.getCurrentPosition();
rightFrontPreMovePosition = rightFront.getCurrentPosition();
leftBackPreMovePosition = leftFront.getCurrentPosition();
rightBackPreMovePosition = rightFront.getCurrentPosition();
leftFrontPower = yAmt + xAmt;
rightFrontPower = yAmt - xAmt;
leftBackPower = yAmt - xAmt;
rightBackPower = yAmt + xAmt;
}
if(yPos > 1000){
yAmt = Math.abs(yAmt);
leftFrontPreMovePosition = leftFront.getCurrentPosition();
rightFrontPreMovePosition = rightFront.getCurrentPosition();
leftBackPreMovePosition = leftFront.getCurrentPosition();
rightBackPreMovePosition = rightFront.getCurrentPosition();
leftFrontPower = yAmt + xAmt;
rightFrontPower = yAmt - xAmt;
leftBackPower = yAmt - xAmt;
rightBackPower = yAmt + xAmt;
}
if(yPos < -1000){
yAmt = -Math.abs(yAmt);
leftFrontPreMovePosition = leftFront.getCurrentPosition();
rightFrontPreMovePosition = rightFront.getCurrentPosition();
leftBackPreMovePosition = leftFront.getCurrentPosition();
rightBackPreMovePosition = rightFront.getCurrentPosition();
leftFrontPower = yAmt + xAmt;
rightFrontPower = yAmt - xAmt;
leftBackPower = yAmt - xAmt;
rightBackPower = yAmt + xAmt;
}
double leftFrontProgress = Math.abs((leftFront.getCurrentPosition() - leftFrontPreMovePosition)/leftFrontPower);
double leftBackProgress = Math.abs((leftBack.getCurrentPosition() - leftBackPreMovePosition)/leftBackPower);
double rightFrontProgress = Math.abs((rightFront.getCurrentPosition() - rightFrontPreMovePosition)/rightFrontPower);
double rightBackProgress = Math.abs((rightBack.getCurrentPosition() - rightBackPreMovePosition)/rightBackPower);
double averageProgress = (leftFrontProgress + leftBackProgress + rightFrontProgress + rightBackProgress)/4;
double sensitivity = 300; // Higher numbers mean more distance before change.
leftFrontMultiplier = 1 + (averageProgress - leftFrontProgress)/sensitivity;
rightFrontMultiplier = 1 + (averageProgress - rightFrontProgress)/sensitivity;
leftBackMultiplier = 1 + (averageProgress - leftBackProgress)/sensitivity;
rightBackMultiplier = 1 + (averageProgress - rightBackProgress)/sensitivity;
loops++;
// telemetry.addData("LF", leftFrontProgress);
// telemetry.addData("RF", rightFrontProgress);
// telemetry.addData("LB", leftBackProgress);
// telemetry.addData("RB", rightBackProgress);
// telemetry.addData("time", time - getRuntime());
// telemetry.addData("x", xPos);
// telemetry.addData("y", yPos);
telemetry.update();
leftFront.setPower(leftFrontPower*leftFrontMultiplier);
rightFront.setPower(rightFrontPower*rightFrontMultiplier);
leftBack.setPower(leftBackPower*leftBackMultiplier);
rightBack.setPower(rightBackPower*rightBackMultiplier);
}
// waitOneSecond();
}
}
}