Skip to content

Commit

Permalink
Some more changes and code optimizations.
Browse files Browse the repository at this point in the history
[SuperComponents]
- SuperComponents now check for duplicate entries before init.
- ComponentInitExceptions are now reported to the DriverStation.
- Removed a bunch of unnecessary code in SuperTalon and SuperVictor.
  • Loading branch information
pacoito123 committed Aug 18, 2019
1 parent 8bfff1c commit 3b0ab24
Show file tree
Hide file tree
Showing 10 changed files with 132 additions and 190 deletions.
6 changes: 3 additions & 3 deletions src/main/java/org/usfirst/lib6647/oi/JController.java
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ public boolean get() {
}

/**
* Method for getting an axisButton input for any value, with 0.15 as tolerance
* Method for getting an axisButton input for any value, with 0.30 as tolerance
* (so as to avoid accidental input due to improper {@link JController}
* calibration).
*
Expand All @@ -201,7 +201,7 @@ public boolean get() {
}

/**
* Method for getting a negative axisButton input, with 0.15 as tolerance (to
* Method for getting a negative axisButton input, with -0.30 as tolerance (to
* avoid accidental input due to improper {@link JController} calibration).
*
* @param controller
Expand All @@ -218,7 +218,7 @@ public boolean get() {
}

/**
* Method for getting a positive axisButton input, with 0.15 as tolerance (to
* Method for getting a positive axisButton input, with 0.30 as tolerance (to
* avoid accidental input due to improper {@link JController} calibration).
*
* @param controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import org.usfirst.lib6647.util.ComponentInitException;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DriverStation;

/**
* Interface to allow {@link Compressor} initialization via JSON. Subsystems
Expand All @@ -35,7 +36,8 @@ default void initCompressors(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("compressors").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("module")) {
if (json.hasNonNull("name") && !compressors.containsKey(json.get("name").asText())
&& json.hasNonNull("module")) {
// Read values from JsonNode.
int module = json.get("module").asInt(-1);

Expand All @@ -53,12 +55,14 @@ default void initCompressors(JsonNode robotMap, String subsystemName) {

// Put object in HashMap with its declared name as key after initialization and
// configuration.
compressors.put(json.get("name").toString(), compressor);
compressors.put(json.get("name").asText(), compressor);
} else
throw new ComponentInitException(String.format(
"[!] UNDECLARED OR EMPTY COMPRESSOR ENTRY IN SUBSYSTEM '%s'", subsystemName.toUpperCase()));
throw new ComponentInitException(
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY COMPRESSOR ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import org.usfirst.lib6647.util.ComponentInitException;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DriverStation;

/**
* Interface to allow {@link DigitalInput} initialization via JSON. Subsystems
Expand Down Expand Up @@ -36,15 +37,16 @@ default void initDigitalInputs(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("digitalInputs").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("channel")) {
if (json.hasNonNull("name") && !digitalInputs.containsKey(json.get("name").asText())
&& json.hasNonNull("channel")) {
// Read values from JsonNode.
int channel = json.get("channel").asInt(-1);

// Check if the required JsonNode values to initialize the object are present.
if (channel < 0)
throw new ComponentInitException(String.format(
"[!] INVALID OR EMPTY CHANNEL VALUE FOR DIGITALINPUT '%1$s' IN SUBSYSTEM '%2$s'",
json.get("name").toString(), subsystemName));
json.get("name").asText(), subsystemName));

// Create DigitalInput object.
DigitalInput digitalInput = new DigitalInput(json.get("channel").asInt());
Expand All @@ -54,13 +56,14 @@ default void initDigitalInputs(JsonNode robotMap, String subsystemName) {

// Put object in HashMap with its declared name as key after initialization and
// configuration.
digitalInputs.put(json.get("name").toString(), digitalInput);
digitalInputs.put(json.get("name").asText(), digitalInput);
} else
throw new ComponentInitException(
String.format("[!] UNDECLARED OR EMPTY DIGITALINPUT ENTRY IN SUBSYSTEM '%s'",
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY DIGITALINPUT ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
import org.usfirst.lib6647.subsystem.hypercomponents.HyperDoubleSolenoid;
import org.usfirst.lib6647.util.ComponentInitException;

import edu.wpi.first.wpilibj.DriverStation;

/**
* Interface to allow {@link HyperDoubleSolenoid} initialization via JSON.
* Subsystems declared need to extend {@link SuperSubsystem} or
Expand Down Expand Up @@ -37,7 +39,8 @@ default void initDoubleSolenoids(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("doubleSolenoids").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("forwardChannel") && json.hasNonNull("reverseChannel")) {
if (json.hasNonNull("name") && !doubleSolenoids.containsKey(json.get("name").asText())
&& json.hasNonNull("forwardChannel") && json.hasNonNull("reverseChannel")) {
// Read values from JsonNode.
int forwardChannel = json.get("forwardChannel").asInt(-1),
reverseChannel = json.get("reverseChannel").asInt(-1);
Expand All @@ -46,7 +49,7 @@ default void initDoubleSolenoids(JsonNode robotMap, String subsystemName) {
if (forwardChannel < 0 || reverseChannel < 0)
throw new ComponentInitException(String.format(
"[!] INVALID OR EMPTY CHANNEL VALUE(S) FOR DOUBLESOLENOID '%1$s' IN SUBSYSTEM '%2$s'",
json.get("name").toString(), subsystemName));
json.get("name").asText(), subsystemName));

// Create HyperDoubleSolenoid object.
HyperDoubleSolenoid doubleSolenoid = new HyperDoubleSolenoid(json.get("forwardChannel").asInt(),
Expand All @@ -58,13 +61,14 @@ default void initDoubleSolenoids(JsonNode robotMap, String subsystemName) {

// Put object in HashMap with its declared name as key after initialization and
// configuration.
doubleSolenoids.put(json.get("name").toString(), doubleSolenoid);
doubleSolenoids.put(json.get("name").asText(), doubleSolenoid);
} else
throw new ComponentInitException(
String.format("[!] UNDECLARED OR EMPTY DOUBLESOLENOID ENTRY IN SUBSYSTEM '%s'",
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY DOUBLESOLENOID ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import org.usfirst.lib6647.util.ComponentInitException;
import org.usfirst.lib6647.util.MotorUtils;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Encoder;

/**
Expand Down Expand Up @@ -36,16 +37,17 @@ default void initEncoders(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("encoders").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("channelA") && json.hasNonNull("channelB")
&& json.hasNonNull("reverse") && json.hasNonNull("encodingType")) {
if (json.hasNonNull("name") && !encoders.containsKey(json.get("name").asText())
&& json.hasNonNull("channelA") && json.hasNonNull("channelB") && json.hasNonNull("reverse")
&& json.hasNonNull("encodingType")) {
// Read values from JsonNode.
int channelA = json.get("channelA").asInt(-1), channelB = json.get("channelB").asInt(-1);

// Check if the required JsonNode values to initialize the object are present.
if (channelA < 0 || channelB < 0)
throw new ComponentInitException(
String.format("[!] INVALID OR EMPTY VALUE(S) FOR ENCODER '%1$s' IN SUBSYSTEM '%2$s'",
json.get("name").toString(), subsystemName));
json.get("name").asText(), subsystemName));

// Create Encoder object.
Encoder encoder = new Encoder(json.get("channelA").asInt(), json.get("channelB").asInt(),
Expand All @@ -59,10 +61,12 @@ default void initEncoders(JsonNode robotMap, String subsystemName) {
// configuration.
encoders.put(json.get("name").asText(), encoder);
} else
throw new ComponentInitException(String.format(
"[!] UNDECLARED OR EMPTY ENCODER ENTRY IN SUBSYSTEM '%s'", subsystemName.toUpperCase()));
throw new ComponentInitException(
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY ENCODER ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import org.usfirst.lib6647.subsystem.SuperSubsystem;
import org.usfirst.lib6647.util.ComponentInitException;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.PowerDistributionPanel;

/**
Expand Down Expand Up @@ -37,7 +38,8 @@ default void initPDPs(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("PDPs").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("module")) {
if (json.hasNonNull("name") && !PDPs.containsKey(json.get("name").asText())
&& json.hasNonNull("module")) {
// Read values from JsonNode.
int module = json.get("module").asInt(-1);

Expand All @@ -57,10 +59,12 @@ default void initPDPs(JsonNode robotMap, String subsystemName) {
// configuration.
PDPs.put(json.get("name").asText(), pdp);
} else
throw new ComponentInitException(String.format(
"[!] UNDECLARED OR EMPTY PDP ENTRY IN SUBSYSTEM '%s'", subsystemName.toUpperCase()));
throw new ComponentInitException(
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY PDP ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
import org.usfirst.lib6647.subsystem.hypercomponents.HyperSolenoid;
import org.usfirst.lib6647.util.ComponentInitException;

import edu.wpi.first.wpilibj.DriverStation;

/**
* Interface to allow {@link HyperSolenoid} initialization via JSON. Subsystems
* declared need to extend {@link SuperSubsystem} or {@link PIDSuperSubsystem}
Expand All @@ -35,7 +37,8 @@ default void initSolenoids(JsonNode robotMap, String subsystemName) {
// Spliterate through each of the elements in the JsonNode.
robotMap.get("solenoids").spliterator().forEachRemaining(json -> {
try {
if (json.hasNonNull("name") && json.hasNonNull("channel")) {
if (json.hasNonNull("name") && !solenoids.containsKey(json.get("name").asText())
&& json.hasNonNull("channel")) {
// Read values from JsonNode.
int channel = json.get("channel").asInt(-1);

Expand All @@ -57,10 +60,12 @@ default void initSolenoids(JsonNode robotMap, String subsystemName) {
// configuration.
solenoids.put(json.get("name").asText(), solenoid);
} else
throw new ComponentInitException(String.format(
"[!] UNDECLARED OR EMPTY SOLENOID ENTRY IN SUBSYSTEM '%s'", subsystemName.toUpperCase()));
throw new ComponentInitException(
String.format("[!] UNDECLARED, DUPLICATE, OR EMPTY SOLENOID ENTRY IN SUBSYSTEM '%s'",
subsystemName.toUpperCase()));
} catch (ComponentInitException e) {
System.out.println(e.getMessage());
DriverStation.reportError(e.getMessage(), false);
}
});
}
Expand All @@ -73,10 +78,6 @@ default void initSolenoids(JsonNode robotMap, String subsystemName) {
* @throws ComponentInitException if {@link JsonNode} key is defined, but empty.
*/
private void setInitialValue(JsonNode json, HyperSolenoid solenoid) throws ComponentInitException {
if (json.get("initialValue").asText().isEmpty())
throw new ComponentInitException(String.format("[!] EMPTY INITIAL VALUE FOR SOLENOID '%s'.",
json.get("name").asText().toUpperCase()));

solenoid.set(json.get("initialValue").asBoolean());
}

Expand Down
Loading

0 comments on commit 3b0ab24

Please sign in to comment.