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

Commit de26026

Browse files
committed
2 parents f7e68ee + 27a4be9 commit de26026

4 files changed

Lines changed: 14 additions & 38 deletions

File tree

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
1-
#Mon Feb 19 20:57:02 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/autonomous/AutoUtils.java

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66

77
public class AutoUtils {
88

9-
public static Position position;
9+
public static Position position = new Position(0, 0, 0);
1010

1111
/**
1212
* Parses the inputted script file into a map of scripts
@@ -25,7 +25,6 @@ public static Map<String, ArrayList<String[]>> parseScriptFile(String scriptFile
2525
String currScriptName = "";
2626

2727
int count = 0;
28-
int errorCount = 0;
2928
for (String line : lines) {
3029
count++;
3130
// remove comments
@@ -76,8 +75,6 @@ public static Map<String, ArrayList<String[]>> parseScriptFile(String scriptFile
7675
if (isValidCommand(instruction, args, count)) {
7776
String[] command = { instruction, args };
7877
currScript.add(command);
79-
} else {
80-
errorCount++;
8178
}
8279
}
8380

@@ -89,8 +86,6 @@ public static Map<String, ArrayList<String[]>> parseScriptFile(String scriptFile
8986
// remove the stray one in the beginning
9087
autoScripts.remove("");
9188

92-
System.out.println("[INFO] Successfuly parsed " + count + " lines with " + errorCount + " errors.");
93-
9489
return autoScripts;
9590
}
9691

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

Lines changed: 2 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,6 @@
99
*/
1010
public class DefaultIntake extends Command {
1111

12-
private boolean manipulatorPluggedIn = true;
13-
1412
public DefaultIntake() {
1513
// Use requires() here to declare subsystem dependencies
1614
// eg. requires(chassis);
@@ -19,21 +17,13 @@ public DefaultIntake() {
1917

2018
// Called just before this Command runs the first time
2119
protected void initialize() {
22-
try {
23-
Robot.oi.manipulator.getRawAxis(1);
24-
} catch (NullPointerException e) {
25-
System.err.println("[ERROR] Manipulator not plugged in.");
26-
manipulatorPluggedIn = false;
27-
}
2820
}
2921

3022
// Called repeatedly when this Command is scheduled to run
3123
protected void execute() {
3224
// 1 and 5 represent the axes' index in driver station
33-
if (manipulatorPluggedIn) {
34-
Robot.intakeEject.runLeftIntake(Robot.oi.manipulator.getRawAxis(1));
35-
Robot.intakeEject.runRightIntake(Robot.oi.manipulator.getRawAxis(5));
36-
}
25+
Robot.intakeEject.runLeftIntake(Robot.oi.manipulator.getRawAxis(1));
26+
Robot.intakeEject.runRightIntake(Robot.oi.manipulator.getRawAxis(5));
3727
}
3828

3929
// Make this return true when this Command no longer needs to run execute()

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

Lines changed: 10 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import edu.wpi.first.wpilibj.PIDOutput;
1010
import edu.wpi.first.wpilibj.PIDSource;
1111
import edu.wpi.first.wpilibj.command.Command;
12+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1213

1314
/**
1415
* Drives the robot a certain target distance using PID. Implements PIDOutput in
@@ -20,9 +21,6 @@ public class PIDMove extends Command implements PIDOutput {
2021
private DrivetrainInterface dt;
2122
private PIDController moveController;
2223
private PIDSource avg;
23-
private SmartDashboardInterface sd;
24-
private double pointX;
25-
private double pointY;
2624

2725
/**
2826
* Constructs this command with a new PIDController. Sets all of the
@@ -45,14 +43,13 @@ public PIDMove(double targ, DrivetrainInterface dt, SmartDashboardInterface sd,
4543
target = targ;
4644
this.dt = dt;
4745
this.avg = avg;
48-
this.sd = sd;
4946
if (Robot.dt != null) {
5047
requires(Robot.dt);
5148
}
5249
double kf = 1 / (dt.getCurrentMaxSpeed() * sd.getConst("Default PID Update Time", 0.05));
5350
moveController = new PIDController(sd.getConst("MovekP", 0.1), sd.getConst("MovekI", 0),
5451
sd.getConst("MovekD", 0), kf, avg, this);
55-
sd.putData("Move PID", moveController);
52+
SmartDashboard.putData("Move PID", moveController);
5653
}
5754

5855
/**
@@ -73,19 +70,20 @@ public PIDMove(double targ, DrivetrainInterface dt, SmartDashboardInterface sd,
7370
* the PIDSorceAverage of the DT's two Encoders
7471
*/
7572
public PIDMove(double[] point, DrivetrainInterface dt, SmartDashboardInterface sd, PIDSource avg) {
76-
pointX = point[0];
77-
pointY = point[1];
73+
double dx = point[0] - AutoUtils.position.getX();
74+
double dy = point[1] - AutoUtils.position.getY();
7875

76+
double dist = Math.sqrt(dx * dx + dy * dy); // pythagorean theorem to find distance
77+
78+
this.target = dist;
7979
this.dt = dt;
8080
this.avg = avg;
81-
this.sd = sd;
8281
if (Robot.dt != null) {
8382
requires(Robot.dt);
8483
}
8584
double kf = 1 / (dt.getCurrentMaxSpeed() * sd.getConst("Default PID Update Time", 0.05));
8685
moveController = new PIDController(sd.getConst("MovekP", 1), sd.getConst("MovekI", 0), sd.getConst("MovekD", 0),
8786
kf, avg, this);
88-
sd.putData("Move PID", moveController);
8987
}
9088

9189
/**
@@ -94,12 +92,6 @@ public PIDMove(double[] point, DrivetrainInterface dt, SmartDashboardInterface s
9492
*/
9593
@Override
9694
public void initialize() {
97-
double dx = pointX - AutoUtils.position.getX();
98-
double dy = pointY - AutoUtils.position.getY();
99-
100-
double dist = Math.sqrt(dx * dx + dy * dy); // pythagorean theorem to find distance
101-
this.target = dist;
102-
10395
dt.resetDistEncs();
10496
moveController.disable();
10597
// input is in inches
@@ -108,7 +100,6 @@ public void initialize() {
108100
moveController.setOutputRange(-1.0, 1.0);
109101
moveController.setContinuous(false);
110102
moveController.setAbsoluteTolerance(Robot.getConst("MoveTolerance", 0.1));
111-
System.out.println("move target = " + target);
112103
moveController.setSetpoint(target);
113104

114105
moveController.enable();
@@ -123,8 +114,8 @@ public void initialize() {
123114
@Override
124115
protected void execute() {
125116
System.out.println("Enc Avg Dist: " + avg.pidGet());
126-
sd.putNumber("Move PID Result", moveController.get());
127-
sd.putNumber("Move PID Error", moveController.getError());
117+
SmartDashboard.putNumber("Move PID Result", moveController.get());
118+
SmartDashboard.putNumber("Move PID Error", moveController.getError());
128119
}
129120

130121
/**
@@ -182,6 +173,6 @@ protected void interrupted() {
182173
@Override
183174
public void pidWrite(double output) {
184175
dt.arcadeDrive(output, 0);
185-
sd.putNumber("Move PID Output", output);
176+
SmartDashboard.putNumber("Move PID Output", output);
186177
}
187178
}

0 commit comments

Comments
 (0)