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

Commit 4e0dad2

Browse files
authored
Merge pull request #109 from DriverStationComputer/better-auto
Better auto; last good competition changes
2 parents 3d0494a + c26a3e2 commit 4e0dad2

File tree

14 files changed

+77
-69
lines changed

14 files changed

+77
-69
lines changed

AAAScripts/scripts.txt

Lines changed: 21 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,11 @@ moveto (0,120) #Drive past auto line
77

88
#Switch
99
RRxx:
10-
moveto (0,155)
11-
turn -90
12-
switch
10+
moveto (0,148) -90
11+
switch 18
12+
moveto (-10, 220)
13+
intake
14+
moveto (-22, 205)
1315

1416
RLxx:
1517
move 56
@@ -76,9 +78,11 @@ moveto (0, 120) #Drive past auto line
7678

7779
#Switch
7880
LLxx:
79-
move 150
80-
turn 90
81-
switch
81+
moveto (0,148) 90
82+
switch 18
83+
moveto (10, 220)
84+
intake
85+
moveto (22, 205)
8286

8387
LRxx:
8488
move 56
@@ -139,17 +143,22 @@ exchange
139143

140144
# Cross Auto Line
141145
Cxxx:
142-
moveto (0,50) (48,50) (48,92) #cross baseline
143-
146+
moveto (0, 12) (40, 88)
144147

145148
# Switch
146149
CRxx:
147-
moveto (0,50) (48,50) (48,85)
148-
switch #deploy switch
150+
moveto (0,15) (50,80) 0
151+
switch 16
152+
move -40
153+
intake
154+
moveto (20, 65)
149155

150156
CLxx:
151-
moveto (0,50) (-56,50) (-56,85)
152-
switch #deploy switch
157+
moveto (0,15) (-60,80) 0
158+
switch 16
159+
move -40
160+
intake
161+
moveto (-30, 65)
153162

154163

155164
# Switch and Exchange

CompSD.xml

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,25 @@
11
<xml version="1.0">
22
<dashboard>
3+
<static-widget class="edu.wpi.first.smartdashboard.gui.elements.CameraServerViewer">
4+
<location x="260" y="17"/>
5+
<width>552</width>
6+
<height>403</height>
7+
<property name="Degrees Rotation" value="180"/>
8+
<property name="Camera Choice" value=""/>
9+
</static-widget>
10+
<widget field="Right Intake Open" type="Boolean" class="edu.wpi.first.smartdashboard.gui.elements.TextBox">
11+
<location x="37" y="250"/>
12+
</widget>
13+
<widget field="Left Intake Open" type="Boolean" class="edu.wpi.first.smartdashboard.gui.elements.TextBox">
14+
<location x="37" y="229"/>
15+
</widget>
316
<widget field="DT is Inverted" type="Boolean" class="edu.wpi.first.smartdashboard.gui.elements.BooleanBox">
417
<location x="11" y="110"/>
518
<width>118</width>
619
<height>59</height>
720
</widget>
821
<widget field="Has Cube" type="Boolean" class="edu.wpi.first.smartdashboard.gui.elements.BooleanBox">
9-
<location x="697" y="463"/>
22+
<location x="1182" y="402"/>
1023
<width>96</width>
1124
<height>30</height>
1225
</widget>
@@ -15,19 +28,6 @@
1528
<width>113</width>
1629
<height>44</height>
1730
</widget>
18-
<static-widget class="edu.wpi.first.smartdashboard.gui.elements.CameraServerViewer">
19-
<location x="783" y="0"/>
20-
<width>571</width>
21-
<height>448</height>
22-
<property name="Camera Choice" value="USB Camera 1"/>
23-
</static-widget>
24-
<static-widget class="edu.wpi.first.smartdashboard.gui.elements.CameraServerViewer">
25-
<location x="191" y="7"/>
26-
<width>586</width>
27-
<height>438</height>
28-
<property name="Degrees Rotation" value="180"/>
29-
<property name="Camera Choice" value=""/>
30-
</static-widget>
3131
<widget field="Move PID Error" type="Number" class="edu.wpi.first.smartdashboard.gui.elements.TextBox">
3232
<location x="173" y="661"/>
3333
</widget>
@@ -129,13 +129,13 @@
129129
</dashboard>
130130
<live-window>
131131
<widget field="Drivetrain" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
132-
<location x="7" y="6"/>
132+
<location x="3" y="14"/>
133133
</widget>
134134
<widget field="ClimberAssist" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
135-
<location x="21" y="22"/>
135+
<location x="9" y="11"/>
136136
</widget>
137137
<widget field="IntakeEject" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
138-
<location x="18" y="28"/>
138+
<location x="30" y="22"/>
139139
</widget>
140140
<widget field="Lift" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
141141
<widget field="PIDController" type="PIDController" class="edu.wpi.first.smartdashboard.gui.elements.PIDEditor">
@@ -153,12 +153,12 @@
153153
<height>46</height>
154154
<width>293</width>
155155
</widget>
156-
<location x="24" y="18"/>
156+
<location x="31" y="11"/>
157157
<width>305</width>
158158
<height>323</height>
159159
</widget>
160160
<widget field="Climber" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
161-
<location x="5" y="16"/>
161+
<location x="23" y="3"/>
162162
</widget>
163163
<widget field="Ungrouped" type="LW Subsystem" class="edu.wpi.first.smartdashboard.livewindow.elements.LWSubsystem">
164164
<widget field="Encoder[1]" type="Quadrature Encoder" class="edu.wpi.first.smartdashboard.livewindow.elements.EncoderDisplay">
@@ -251,7 +251,7 @@
251251
<height>20</height>
252252
<width>326</width>
253253
</widget>
254-
<location x="6" y="24"/>
254+
<location x="8" y="22"/>
255255
<width>338</width>
256256
<height>974</height>
257257
</widget>

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
import org.usfirst.frc.team199.Robot2018.commands.PIDTurn;
1919
import org.usfirst.frc.team199.Robot2018.commands.ResetEncoders;
2020
import org.usfirst.frc.team199.Robot2018.commands.SetDistancePerPulse;
21-
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;
2221
import org.usfirst.frc.team199.Robot2018.commands.ShiftHighGear;
2322
import org.usfirst.frc.team199.Robot2018.commands.ShiftLowGear;
2423
import org.usfirst.frc.team199.Robot2018.commands.StopIntake;
@@ -44,7 +43,7 @@ public class OI {
4443
public Joystick rightJoy;
4544
private JoystickButton shiftLowGearButton;
4645
private JoystickButton shiftHighGearButton;
47-
private JoystickButton shiftDriveTypeButton;
46+
// private JoystickButton shiftDriveTypeButton;
4847
private JoystickButton pIDMoveButton;
4948
private JoystickButton pIDTurnButton;
5049
private JoystickButton resetEncButton;
@@ -82,8 +81,9 @@ public int getButton(String key, int def) {
8281

8382
public OI(Robot robot) {
8483
leftJoy = new Joystick(0);
85-
shiftDriveTypeButton = new JoystickButton(leftJoy, getButton("Shift Drive Type", 2));
86-
shiftDriveTypeButton.whenPressed(new ShiftDriveType());
84+
// shiftDriveTypeButton = new JoystickButton(leftJoy, getButton("Shift Drive
85+
// Type", 2));
86+
// shiftDriveTypeButton.whenPressed(new ShiftDriveType());
8787

8888
invertDTButton = new JoystickButton(leftJoy, getButton("Invert Drivetrain", 3));
8989
invertDTButton.whenPressed(new InvertDrivetrain());

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -183,8 +183,8 @@ public void robotInit() {
183183

184184
listen = new Listener();
185185
lift.resetEnc();
186-
CameraServer.getInstance().startAutomaticCapture(0);
187-
CameraServer.getInstance().startAutomaticCapture(1);
186+
// CameraServer.getInstance().startAutomaticCapture(0);
187+
CameraServer.getInstance().startAutomaticCapture((int) Robot.getConst("Camera Port", 1));
188188
}
189189

190190
/**

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

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -109,21 +109,21 @@ public static boolean isValidCommand(String instruction, String args, int lineNu
109109
// moveto takes in a set of points, and the last arg can be a number
110110
if (instruction.equals("moveto")) {
111111
if (args == "") {
112-
logError(lineNumber, "The command `moveto` requires at least one argument.");
112+
logError(lineNumber, "The command `" + instruction + "` requires at least one argument.");
113113
return false;
114114
}
115115

116116
String[] splitArgs = args.split(" ");
117117
for (int i = 0; i < splitArgs.length - 1; i++) {
118118
if (!isPoint(splitArgs[i])) {
119119
logError(lineNumber,
120-
"The arguments for command `moveto` should be points formatted like this: " + "`(x,y)`.");
120+
"The arguments for command `" + instruction + "` should be points formatted like this: " + "`(x,y)`.");
121121
return false;
122122
}
123123
}
124124

125125
if (!isDouble(splitArgs[splitArgs.length - 1]) && !isPoint(splitArgs[splitArgs.length - 1])) {
126-
logError(lineNumber, "The last argument for command `moveto` should be a number, or a point "
126+
logError(lineNumber, "The last argument for command `" + instruction + "` should be a number, or a point "
127127
+ "formatted like this: `(x,y)`.");
128128
return false;
129129
}
@@ -132,32 +132,32 @@ public static boolean isValidCommand(String instruction, String args, int lineNu
132132
// turn can take a number or point
133133
else if (instruction.equals("turn")) {
134134
if (args.contains(" ")) {
135-
logError(lineNumber, "Command `turn` only accepts one argument.");
135+
logError(lineNumber, "Command `" + instruction + "` only accepts one argument.");
136136
return false;
137137
}
138138

139139
if (!isDouble(args) && !isPoint(args)) {
140-
logError(lineNumber, "The argument for command `turn` should be a number or a point formatted like "
140+
logError(lineNumber, "The argument for command `" + instruction + "` should be a number or a point formatted like "
141141
+ "this: `(x,y)`.");
142142
return false;
143143
}
144144
}
145145

146-
// move and wait can take only a number
147-
else if (instruction.equals("move") || instruction.equals("wait")) {
146+
// these can take only a number
147+
else if (instruction.equals("move") || instruction.equals("wait") || instruction.equals("switch") || instruction.equals("scale")) {
148148
if (args.contains(" ")) {
149-
logError(lineNumber, "Command `move` only accepts one argument.");
149+
logError(lineNumber, "Command `" + instruction + "` only accepts one argument.");
150150
return false;
151151
}
152152

153153
if (!isDouble(args)) {
154-
logError(lineNumber, "The argument for command `move` should be a number.");
154+
logError(lineNumber, "The argument for command `" + instruction + "` should be a number.");
155155
return false;
156156
}
157157
}
158158

159159
// switch, scale, exchange, intake, and end all don't have any args
160-
else if (instruction.equals("switch") || instruction.equals("scale") || instruction.equals("exchange")
160+
else if (instruction.equals("exchange")
161161
|| instruction.equals("intake") || instruction.equals("end")) {
162162
if (!args.equals("")) {
163163
logError(lineNumber, "Command `" + instruction + "` does not accept any arguments.");
@@ -168,7 +168,7 @@ else if (instruction.equals("switch") || instruction.equals("scale") || instruct
168168
// Jump only takes one argument
169169
else if (instruction.equals("jump")) {
170170
if (args.contains(" ")) {
171-
logError(lineNumber, "Command `jump` only accepts one argument.");
171+
logError(lineNumber, "Command `" + instruction + "` only accepts one argument.");
172172
return false;
173173
}
174174
}

Robot2018/src/org/usfirst/frc/team199/Robot2018/autonomous/aaa-reference.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ Ex:
5050
| jump | Jumps to the specified script and continues the current script when finished. (Doesn’t make the robot go up.) | `jump MoveToRScale`
5151
| move | Move forward or backwards for the specified amount in inches, relative to the current position. | `move 24` |
5252
| moveto | Move to 1 or more points, sequentially, with an optional last value having a final angle to face towards, all relative to the starting position. | `moveto (12,0) (36,12)` <br> `moveto (0,12) 90` |
53-
| scale | Place a cube at scale height. | `scale` |
54-
| switch | Place a cube at switch height. | `switch` |
53+
| scale | Place a cube at scale height after moving forward by the specified amount with the lift up, and after moves 12 inches back. | `scale 24` |
54+
| switch | Place a cube at switch height after moving forward by the specified amount with the lift up, and after moves 12 inches back. | `switch 24` |
5555
| turn | Turn towards a relative point or rotate clockwise by an angle in degrees, relative to the current position. <br> Negative angle for counterclockwise. | `turn (36,48)` <br> `turn 45` |
5656
| wait | Waits for the number of seconds before proceeding to next command. | `wait 5` |

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

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,7 @@ public class AutoLift extends CommandGroup {
1313
public AutoLift(Lift lift, String height) {
1414
if (height.equals("GROUND")) {
1515
addSequential(new LiftToPosition(lift, LiftHeight.toLH("HOLD_CUBE")));
16-
addSequential(new LiftToPosition(lift, LiftHeight.toLH(height)));
17-
} else {
18-
addSequential(new LiftToPosition(lift, LiftHeight.toLH(height)));
1916
}
17+
addSequential(new LiftToPosition(lift, LiftHeight.toLH(height)));
2018
}
2119
}

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

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,11 @@
99
*/
1010
public class EjectToScale extends CommandGroup {
1111

12-
public EjectToScale() {
12+
public EjectToScale(double dist) {
1313
addSequential(new AutoLift(Robot.lift, "SCALE"));
14-
addSequential(
15-
new PIDMove(Robot.getConst("Auto Scale Move Dist", 18), Robot.dt, Robot.sd, Robot.dt.getDistEncAvg()));
14+
addSequential(new PIDMove(dist, Robot.dt, Robot.sd, Robot.dt.getDistEncAvg()));
1615
addSequential(new OuttakeCube());
17-
addSequential(new PIDMove(-1 * Robot.getConst("Auto Scale Move Dist", 18), Robot.dt, Robot.sd,
16+
addSequential(new PIDMove(-1 * Robot.getConst("Scale move back dist", 12), Robot.dt, Robot.sd,
1817
Robot.dt.getDistEncAvg()));
1918
addSequential(new AutoLift(Robot.lift, "GROUND"));
2019
}

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

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,11 @@
99
*/
1010
public class EjectToSwitch extends CommandGroup {
1111

12-
public EjectToSwitch() {
12+
public EjectToSwitch(double dist) {
1313
addSequential(new AutoLift(Robot.lift, "SWITCH"));
14-
addSequential(
15-
new PIDMove(Robot.getConst("Auto Switch Move Dist", 18), Robot.dt, Robot.sd, Robot.dt.getDistEncAvg()));
14+
addSequential(new PIDMove(dist, Robot.dt, Robot.sd, Robot.dt.getDistEncAvg()));
1615
addSequential(new OuttakeCube());
17-
addSequential(new PIDMove(-1 * Robot.getConst("Auto Switch Move Dist", 18), Robot.dt, Robot.sd,
16+
addSequential(new PIDMove(-1 * Robot.getConst("Switch move back dist", 12), Robot.dt, Robot.sd,
1817
Robot.dt.getDistEncAvg()));
1918
addSequential(new AutoLift(Robot.lift, "GROUND"));
2019
}

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

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,9 @@ public LiftToPosition(Lift lift, LiftHeight goal) {
2424
// Called just before this Command runs the first time
2525
@Override
2626
protected void initialize() {
27-
lift.getPIDController().setPID(Robot.getConst("LiftkP", 0.1), Robot.getConst("LiftkI", 0),
28-
Robot.getConst("LiftkD", 0), Robot.getConst("LiftkF", 0.1));
27+
// lift.getPIDController().setPID(Robot.getConst("LiftkP", 0.1),
28+
// Robot.getConst("LiftkI", 0),
29+
// Robot.getConst("LiftkD", 0), Robot.getConst("LiftkF", 0.1));
2930
double setpoint = lift.getDesiredDistFromPos(pos);
3031
lift.setSetpoint(setpoint);
3132
System.out.println("Target Height: " + setpoint);

0 commit comments

Comments
 (0)