Skip to content
This repository was archived by the owner on Sep 14, 2019. It is now read-only.

Commit b507e2a

Browse files
start testing auto
1 parent f6c2870 commit b507e2a

6 files changed

Lines changed: 29 additions & 28 deletions

File tree

AAAScripts/scripts.txt

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ RxLx:
3636
#-------------------------------------------------
3737

3838
#Exchange
39-
RxxE
39+
RxxE:
4040
moveto (0, 188.4) (-210.6, 188.4) (-210.6, 44.4) (-123.6, 44.4) (-123.6, -39.6) 180 #Curve around switch for baseline #then go to exchange
4141
exchange
4242

@@ -144,7 +144,7 @@ LxRx:
144144
#-------------------------------------------------
145145

146146
#Exchange
147-
LxxE
147+
LxxE:
148148
moveto (0, 188.4) (210.6, 188.4) (210.6, 3.7) (124.8, 3.7) (124.8, -3.3) 180 #Curve around switch for baseline then go to exchange
149149
exchange
150150

@@ -244,13 +244,13 @@ moveto (48,80.375) #cross baseline
244244
CRxx:
245245
moveto (0,60) 90 #5 feet forward, turn 90
246246
moveto (48,60) -90 #4 feet right,turn -90
247-
moveto(48,104.375) #7 feet forward until against switch enclosure, compensating for robot length
247+
moveto (48,104.375) #7 feet forward until against switch enclosure, compensating for robot length
248248
switch #deploy switch
249249

250250
CLxx:
251251
moveto (0,60) -90 #5 feet forward, turn -90
252252
moveto (-48,60) 90 #4 feet left,turn 90
253-
moveto(-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
253+
moveto (-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
254254
switch #deploy switch
255255

256256

@@ -275,7 +275,7 @@ scale #deploy scale
275275
CRLx:
276276
moveto (0,60) 90 #5 feet forward, turn 90
277277
moveto (48,60) -90 #4 feet right,turn -90
278-
moveto(48,104.375) #7 feet forward until against switch enclosure
278+
moveto (48,104.375) #7 feet forward until against switch enclosure
279279
switch #deploy switch
280280
move -39 #move 39 inches back
281281
turn -90 #turn -90 degrees
@@ -294,7 +294,7 @@ scale #deploy scale2
294294
CRRx:
295295
moveto (0,60) 90 #5 feet forward, turn 90
296296
moveto (48,60) -90 #4 feet right,turn -90
297-
moveto(48,104.375) #7 feet forward until against switch enclosure
297+
moveto (48,104.375) #7 feet forward until against switch enclosure
298298
switch #deploy switch
299299
move -39 #move 39 inches back
300300
turn -90 #turn -90 degrees
@@ -313,7 +313,7 @@ scale #deploy scale
313313
CLRx:
314314
moveto (0,60) -90 #5 feet forward, turn -90
315315
moveto (-48,60) 90 #4 feet left,turn 90
316-
moveto(-48,104.375) #7 feet forward until against switch enclosure
316+
moveto (-48,104.375) #7 feet forward until against switch enclosure
317317
switch #deploy switch
318318
move -39 #move 39 inches back
319319
turn -90 #turn -90 degrees
@@ -331,7 +331,7 @@ scale #deploy scale
331331
CLLx:
332332
moveto (0,60) -90 #5 feet forward, turn -90
333333
moveto (-48,60) 90 #4 feet left,turn 90
334-
moveto(-48,104.375) #7 feet forward until against switch enclosure
334+
moveto (-48,104.375) #7 feet forward until against switch enclosure
335335
switch #deploy switch
336336
move -39 #move 39 inches back
337337
turn 90 #turn 90 degrees
@@ -352,7 +352,7 @@ scale #deploy scale2
352352
CRxE:
353353
moveto (0,60) 90 #5 feet forward, turn 90
354354
moveto (48,60) -90 #4 feet right,turn -90
355-
moveto(48,104.375) #7 feet forward until against switch enclosure, compensating for robot length
355+
moveto (48,104.375) #7 feet forward until against switch enclosure, compensating for robot length
356356
switch #deploy switch
357357
move -24 # 2 feet back
358358
turn -90
@@ -368,7 +368,7 @@ exchange
368368
CLxE:
369369
moveto (0,60) -90 #5 feet forward, turn -90
370370
moveto (-48,60) 90 #3 feet left,turn 90
371-
moveto(-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
371+
moveto (-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
372372
switch #deploy switch
373373
move -24
374374
turn 90
@@ -383,7 +383,7 @@ exchange
383383
CxxE:
384384
moveto (0,60) -90 #5 feet forward, turn -90
385385
moveto (-48,60) 90 #3 feet left,turn 90
386-
moveto(-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
386+
moveto (-48,104.375) #7 feet forward until against switch enclosure,compensating for robot length
387387
move -96 #move 8 feet back
388388
turn 180 #turn 180 degrees to face the exchange
389389
exchange
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
1-
#Sun Feb 18 15:40:25 PST 2018
1+
#Sun Feb 18 17:40:43 PST 2018
22
C\:\\Users\\dean\\git\\RobotCode2018\\Robot2018\\lib\\libpathfinderjava.so=4087ee38c338446b8305f67716260df4

Robot2018/src/org/usfirst/frc/team199/Robot2018/Robot.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -169,8 +169,8 @@ public void autonomousInit() {
169169
strategies.put(key, chooser.getSelected());
170170
}
171171

172-
Autonomous auto = new Autonomous(startPos, strategies, autoDelay, fmsInput, false);
173-
auto.start();
172+
Scheduler.getInstance().add(new Autonomous(startPos, strategies, autoDelay, fmsInput, false));
173+
// auto.start();
174174
}
175175

176176
/**

Robot2018/src/org/usfirst/frc/team199/Robot2018/autonomous/AutoUtils.java

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -24,23 +24,24 @@ public static Map<String, ArrayList<String[]>> parseScriptFile(String scriptFile
2424
ArrayList<String[]> currScript = new ArrayList<String[]>();
2525
String currScriptName = "";
2626

27-
int count = 1;
27+
int count = 0;
2828
for (String line : lines) {
29+
count++;
2930
// remove comments
3031
int commentIndex = line.indexOf("#");
3132
if (commentIndex != -1)
3233
line = line.substring(0, commentIndex);
3334

3435
// trim and remove extra whitespace just to make it neater
35-
line = line.trim().replaceAll("\\s+", " ");
36+
line = line.trim().replaceAll("\\s+", " ");
3637
// make coordinates with spaces also work
3738
int parenIndex = line.indexOf("(");
3839
while (parenIndex != -1) {
3940
// removes all spaces between the parentheses
4041
int endParenIndex = line.indexOf(")", parenIndex);
4142
String coord = line.substring(parenIndex + 1, endParenIndex);
4243
line = line.substring(0, parenIndex + 1) + coord.replaceAll(" ", "") + line.substring(endParenIndex);
43-
44+
4445
// finds next parentheses
4546
parenIndex = line.indexOf("(", parenIndex + 1);
4647
}
@@ -76,7 +77,7 @@ public static Map<String, ArrayList<String[]>> parseScriptFile(String scriptFile
7677
currScript.add(command);
7778
}
7879
}
79-
count++;
80+
8081
}
8182

8283
// puts the last script in
@@ -187,7 +188,7 @@ else if (instruction.equals("jump")) {
187188
* the message to log
188189
*/
189190

190-
private static void logWarning (int lineNumber, String message) {
191+
private static void logWarning(int lineNumber, String message) {
191192
System.err.println("[ERROR] Line " + lineNumber + ": " + message);
192193
}
193194

@@ -246,13 +247,13 @@ public static double[] parsePoint(String cmdArgs) {
246247
if (AutoUtils.isPoint(cmdArgs)) {
247248
parentheseless = cmdArgs.substring(1, cmdArgs.length() - 1);
248249
pointparts = parentheseless.split(",");
249-
try {
250-
point[0] = Double.parseDouble(pointparts[0]);
251-
point[1] = Double.parseDouble(pointparts[1]);
252-
} catch (Exception e) {
253-
point[0] = 1;
254-
point[1] = 1;
255-
}
250+
try {
251+
point[0] = Double.parseDouble(pointparts[0]);
252+
point[1] = Double.parseDouble(pointparts[1]);
253+
} catch (Exception e) {
254+
point[0] = 1;
255+
point[1] = 1;
256+
}
256257
}
257258
return point;
258259
}

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDMove.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ public void initialize() {
100100
moveController.setOutputRange(-1.0, 1.0);
101101
moveController.setContinuous(false);
102102
moveController.setAbsoluteTolerance(Robot.getConst("MoveTolerance", 0.1));
103-
moveController.setSetpoint(Robot.getConst("Move Targ", 24));
103+
moveController.setSetpoint(target);
104104

105105
moveController.enable();
106106
// dt.enableVelocityPIDs();

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDTurn.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,7 @@ protected void initialize() {
149149
turnController.setOutputRange(Robot.getConst("Output", 0.5) * -1, Robot.getConst("Output", 0.5));
150150
turnController.setContinuous(true);
151151
turnController.setAbsoluteTolerance(Robot.getConst("TurnTolerance", 1));
152-
double newSetPoint = Robot.getConst("Turn Targ", 90) + dt.getAHRSAngle();
152+
double newSetPoint = target + dt.getAHRSAngle();
153153
while (Math.abs(newSetPoint) > 180) {
154154
newSetPoint = newSetPoint - Math.signum(newSetPoint) * 360;
155155
}

0 commit comments

Comments
 (0)