Skip to content

Commit

Permalink
Merge pull request #19 from hammerhead226/minchingtonak/filenotfound-…
Browse files Browse the repository at this point in the history
…crashfix

Minchingtonak/filenotfound crashfix
  • Loading branch information
minchingtonak authored Mar 22, 2018
2 parents ac0abc4 + 484eaed commit ebc1208
Show file tree
Hide file tree
Showing 7 changed files with 78 additions and 21 deletions.
4 changes: 3 additions & 1 deletion src/org/hammerhead226/sharkmacro/Parser.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ public abstract class Parser {
/**
* Filename to read from or write a new file with.
*/
private final String filename;
protected final String filename;

/**
* HashMap object representing a cache of all previously loaded
Expand Down Expand Up @@ -117,8 +117,10 @@ protected List<String[]> readFromFile() {
reader.close();
} catch (FileNotFoundException e) {
e.printStackTrace();
return null;
} catch (IOException e) {
e.printStackTrace();
return null;
}

cache.put(filename, rawFile);
Expand Down
30 changes: 23 additions & 7 deletions src/org/hammerhead226/sharkmacro/actions/ActionList.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

import org.hammerhead226.sharkmacro.Constants;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Notifier;
import edu.wpi.first.wpilibj.Timer;

Expand Down Expand Up @@ -33,7 +34,7 @@ public class ActionList implements Iterable<Action> {
* Represents whether this {@link ActionList} has finished executing.
*/
private boolean isFinished = false;

/**
* Object that takes a runnable class and starts a new thread to call its
* {@link java.lang.Runnable#run() run()} method periodically.
Expand Down Expand Up @@ -74,9 +75,23 @@ public Iterator<Action> iterator() {
* This method starts the execution process of this {@link ActionList}.
*/
public void execute() {
isFinished = false;
timer.start();
thread.startPeriodic(Constants.DT_SECONDS);
if (this.actionList != null) {
isFinished = false;
timer.start();
thread.startPeriodic(Constants.DT_SECONDS);
} else {
DriverStation.getInstance();
DriverStation.reportError("Tried to execute empty ActionList!", false);
}
}

/**
* Should be called during execution if the process is interrupted. Stops execution.
*/
public void onInterrupt() {
timer.stop();
timer.reset();
thread.stop();
}

/**
Expand All @@ -95,9 +110,9 @@ public boolean isFinished() {
* {@link PeriodicRunnable#run() run()} periodically.
*/
class PeriodicRunnable implements java.lang.Runnable {

private ActionList al;

public PeriodicRunnable(ActionList al) {
this.al = al;
}
Expand Down Expand Up @@ -126,7 +141,8 @@ public void run() {
}

/**
* String representation of each {@link Action} contained in this {@link ActionList}.
* String representation of each {@link Action} contained in this
* {@link ActionList}.
*
* @return the string representation
*/
Expand Down
11 changes: 10 additions & 1 deletion src/org/hammerhead226/sharkmacro/actions/ActionListParser.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
import org.hammerhead226.sharkmacro.Parser;
import org.hammerhead226.sharkmacro.motionprofiles.Profile;

import edu.wpi.first.wpilibj.DriverStation;

/**
* Handles the reading and writing of {@link ActionList}s.
*
Expand Down Expand Up @@ -37,7 +39,8 @@ public ActionListParser(String filename) {
*/
public boolean writeToFile(ActionList al) {
if (al.getSize() == 0) {
System.out.println("Tried to write empty ActionList");
DriverStation.getInstance();
DriverStation.reportWarning("Tried to write empty ActionList!", false);
return false;
}

Expand Down Expand Up @@ -65,6 +68,12 @@ public boolean writeToFile(ActionList al) {
public ActionList toObject() {

List<String[]> actionListRaw = readFromFile();

if (actionListRaw == null) {
DriverStation.getInstance();
DriverStation.reportError("Tried to load nonexistant ActionList from name: " + super.filename, false);
return new ActionList(null);
}

ArrayList<Action> list = new ArrayList<Action>(Constants.ACTIONRECORDER_LIST_DEFAULT_LENGTH);
for (String[] s : actionListRaw) {
Expand Down
34 changes: 26 additions & 8 deletions src/org/hammerhead226/sharkmacro/motionprofiles/Profile.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import java.util.Arrays;

import com.ctre.CANTalon;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj.DriverStation;
Expand Down Expand Up @@ -64,13 +63,17 @@ public class Profile {
* @param rightTalon
* the Talon to execute the right profile with
*/
public Profile(double[][] leftProfile, double[][] rightProfile, TalonSRX leftTalon, TalonSRX rightTalon) {
public Profile(double[][] leftProfile, double[][] rightProfile, TalonSRX leftTalon, TalonSRX rightTalon,
int leftPidSlotIdx, int rightPidSlotIdx) {
this.leftProfile = leftProfile;
this.rightProfile = rightProfile;
this.leftTalon = leftTalon;
this.rightTalon = rightTalon;
this.length = this.leftProfile.length;
this.dt = (int) this.leftProfile[0][2];

handler = new ProfileHandler(new double[][][] { leftProfile, rightProfile },
new TalonSRX[] { leftTalon, rightTalon }, new int[] { leftPidSlotIdx, rightPidSlotIdx });
}

/**
Expand All @@ -87,13 +90,18 @@ public Profile(double[][] leftProfile, double[][] rightProfile, TalonSRX leftTal
* @param rightTalon
* the Talon to execute the right profile with
*/
public Profile(String[][] leftProfile, String[][] rightProfile, TalonSRX leftTalon, TalonSRX rightTalon) {
public Profile(String[][] leftProfile, String[][] rightProfile, TalonSRX leftTalon, TalonSRX rightTalon,
int leftPidSlotIdx, int rightPidSlotIdx) {
this.leftProfile = toDoubleArray(leftProfile);
this.rightProfile = toDoubleArray(rightProfile);
this.leftTalon = leftTalon;
this.rightTalon = rightTalon;
this.length = this.leftProfile.length;
this.dt = (int) this.leftProfile[0][2];

handler = new ProfileHandler(new double[][][] { this.leftProfile, this.rightProfile },
new TalonSRX[] { leftTalon, rightTalon }, new int[] { leftPidSlotIdx, rightPidSlotIdx });

}

/**
Expand All @@ -106,10 +114,13 @@ public Profile(String[][] leftProfile, String[][] rightProfile, TalonSRX leftTal
* @param rightGainsProfile
* the PID slot index to use to execute the right motion profile
*/
public void execute(int leftPidSlotIdx, int rightPidSlotIdx) {
handler = new ProfileHandler(new double[][][] { leftProfile, rightProfile },
new TalonSRX[] { leftTalon, rightTalon }, new int[] { leftPidSlotIdx, rightPidSlotIdx });
handler.execute();
public void execute() {
if (leftProfile.length != 0 && rightProfile.length != 0) {
handler.execute();
} else {
DriverStation.getInstance();
DriverStation.reportError("Tried to run empty profile!", false);
}
}

/**
Expand All @@ -121,7 +132,8 @@ public void onInterrupt() {
if (handler != null) {
handler.onInterrupt();
} else {
DriverStation.getInstance().reportWarning("No instance of ProfileHandler to interrupt!", false);
DriverStation.getInstance();
DriverStation.reportWarning("No instance of ProfileHandler to interrupt!", false);
}
}

Expand Down Expand Up @@ -184,6 +196,9 @@ public String[][] getRightProfile_String() {
* @return the converted array
*/
private static String[][] toStringArray(double[][] arr) {
if (arr.length == 0) {
return new String[0][0];
}
String[][] str = new String[arr.length][arr[0].length];
int i = 0;
for (double[] d : arr) {
Expand All @@ -201,6 +216,9 @@ private static String[][] toStringArray(double[][] arr) {
* @return the converted array
*/
private static double[][] toDoubleArray(String[][] arr) {
if (arr.length == 0) {
return new double[0][0];
}
double[][] dbl = new double[arr.length][arr[0].length];
int i = 0;
for (String[] s : arr) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,10 @@ public ProfileHandler(final double[][][] profiles, TalonSRX[] talons, int[] pidS
}

executorThread = new Notifier(new PeriodicExecutor());

fillTalonsWithMotionProfile();
DriverStation.getInstance();
DriverStation.reportWarning("PROFILE LOADED", false);
}

/**
Expand Down
12 changes: 10 additions & 2 deletions src/org/hammerhead226/sharkmacro/motionprofiles/ProfileParser.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@

import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj.DriverStation;

/**
* Handles the reading and writing of {@link Profile}s.
*
Expand Down Expand Up @@ -62,8 +64,14 @@ public boolean writeToFile(Profile profile) {
*
* @return a new {@code Profile} instance
*/
public Profile toObject(TalonSRX leftTalon, TalonSRX rightTalon) {
public Profile toObject(TalonSRX leftTalon, TalonSRX rightTalon, int leftPidSlotIdx, int rightPidSlotIdx) {
List<String[]> profileRaw = readFromFile();

if (profileRaw == null) {
DriverStation.getInstance();
DriverStation.reportError("Tried to load nonexistant Profile from name: " + super.filename, false);
return new Profile(new double[0][0], new double[0][0], leftTalon, rightTalon, leftPidSlotIdx, rightPidSlotIdx);
}

// Process read values into Profile
String[][] left = new String[profileRaw.size()][3];
Expand All @@ -79,7 +87,7 @@ public Profile toObject(TalonSRX leftTalon, TalonSRX rightTalon) {
right[i][2] = profileRaw.get(i)[4];
}

Profile p = new Profile(left, right, leftTalon, rightTalon);
Profile p = new Profile(left, right, leftTalon, rightTalon, leftPidSlotIdx, rightPidSlotIdx);

return p;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ public Recording(ArrayList<ArrayList<Double>> recordings, TalonSRX leftTalon, Ta
*
* @return a new {@link Profile} containing the new motion profiles
*/
public Profile toProfile() {
public Profile toProfile(int leftPidSlotIdx, int rightPidSlotIdx) {

// Remove differential in list size
int minSize = Integer.MAX_VALUE;
Expand Down Expand Up @@ -100,7 +100,7 @@ public Profile toProfile() {
rightProfile[i][1] = rightFeedforwardValues.get(i);
rightProfile[i][2] = Constants.DT_MS;
}
return new Profile(leftProfile, rightProfile, leftTalon, rightTalon);
return new Profile(leftProfile, rightProfile, leftTalon, rightTalon, leftPidSlotIdx, rightPidSlotIdx);
}

/**
Expand Down

0 comments on commit ebc1208

Please sign in to comment.