Skip to content

Commit 96d5aef

Browse files
Nummun14levyishai
andauthored
General Update (#19)
* started cleaning was in the middle of TalonFX * added a BUNCH more jDocs. (I'm litterally falling asleep rn) just finished MirrorablePose2d * finished adding jDocs * grammer sucks * updated libraries and adapted code to it * javadocs are annoying. So is REV. So am I. * "Javadocs are actually quite fun" - Ezra Gryn 2024 * erm actually🤓 * JAVADOCS!!! and mirroable fix * updated wpilib tools * maybe firxed SimpleMotorSimulation? (I know the jdoc isn't good, I'll fix it soon) * did a bit of the review, will soon finish it * removed this for ezra (Your welcome, good luck on the math test :)) * sim thing * "Explain more" * improve simplemotorsim jdoc * maybe improved spark sim logic * made config better * jdocs and sim logic * improve mechanism constructers * REVSucksConstants * spark sim still isn't working. (but I'm hoOolding on(epic is playing in the background))) * javadocs suck, spit, stop, and setPosition * Removed annoying javadoc warnings * threaded signal javadocs, and sim logic, will keep working on it later. Shabbat Shalom * imrproved spark encoder methods, and temporeraly removed mirroable bug fix * added docs for cancoder and gyro, and cleaned up mirrorable * corrected led naming * idea for mirrorable fix * cleaned up mirrorable solution * idea for mirrorable fix * 🥸🫨🙂‍↔️🤒🧐mirrorable * updated limelight helpers, fixed led jdocs, reverted to old mirrorable fix * cleaned up mirrorable, and spark. Still trying to figure out revSim * mirrorable, gyro, cancoder cleanup. SparkSim logic changes * removed redundent if statement, and added temporary debugging stuff for sparksim * improved jdocs, and changed some SparkSim logic, still doesn't work though * jdoc and encoder sim * sim encoder logic stuff. Sim still isn't working * debugging * whitespaces and cleaning * added debugging sout * more souts * logging * id * print * sout * * 60 * units. Also, Yishai you really never tested the code * docs and logs * changed encoder logic stuff * camel case, and removed testing * cleaned up solution. SIM WORKS!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! * cleaning, and made motor sim get system or rotor depending on the encoder * cleaned velocity calc * no longer ew * method name * javadocs * jdocs and "ecnoders * javadocs * docs and sim --------- Co-authored-by: Yishai Levy <[email protected]>
1 parent 21aba14 commit 96d5aef

File tree

62 files changed

+1681
-674
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

62 files changed

+1681
-674
lines changed

build.gradle

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
plugins {
2-
id "java"
2+
id "java-library"
33
id "maven-publish"
4-
id "edu.wpi.first.GradleRIO" version "2024.3.2"
5-
id "edu.wpi.first.WpilibTools" version "1.3.0"
4+
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
5+
id "edu.wpi.first.WpilibTools" version "2.1.0"
66
}
77

88
java {
@@ -51,6 +51,7 @@ wpi.java.configureTestTasks(test)
5151
// Configure string concat to always inline compile
5252
tasks.withType(JavaCompile) {
5353
options.compilerArgs.add '-XDstringConcat=inline'
54+
javadoc.options.addStringOption('Xdoclint:none', '-quiet')
5455
}
5556

5657
task sourcesJar(type: Jar, dependsOn: classes) {

src/main/java/org/trigon/commands/ExecuteEndCommand.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,4 +18,4 @@ public ExecuteEndCommand(Runnable onExecute, Runnable onEnd, SubsystemBase... re
1818
super(() -> {
1919
}, onExecute, (interrupted) -> onEnd.run(), () -> false, requirements);
2020
}
21-
}
21+
}

src/main/java/org/trigon/hardware/BaseInputs.java

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,11 @@ public abstract class BaseInputs implements LoggableInputs {
1111
private final String name;
1212
private double lastErrorTimestamp = 0;
1313

14+
/**
15+
* Creates a new BaseInputs instance.
16+
*
17+
* @param name the name of the instance. Used for error messages
18+
*/
1419
public BaseInputs(String name) {
1520
this.name = name;
1621
}
@@ -20,6 +25,12 @@ public void fromLog(LogTable table) {
2025
latestTable = table;
2126
}
2227

28+
/**
29+
* Gets a signal from the inputs.
30+
*
31+
* @param signalName the name of the signal
32+
* @return the signal
33+
*/
2334
public double getSignal(String signalName) {
2435
if (latestTable == null) {
2536
if (shouldPrintError())
@@ -37,6 +48,13 @@ public double getSignal(String signalName) {
3748
return value.getDouble();
3849
}
3950

51+
/**
52+
* Gets a threaded signal.
53+
* Threaded signals use threading to process certain signals separately at a faster rate.
54+
*
55+
* @param signalName the name of the threaded signal
56+
* @return the threaded signal
57+
*/
4058
public double[] getThreadedSignal(String signalName) {
4159
if (latestTable == null) {
4260
if (shouldPrintError())
Lines changed: 39 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,40 +1,78 @@
11
package org.trigon.hardware;
22

3+
/**
4+
* A class that contains stats about the robot's hardware.
5+
*/
36
public class RobotHardwareStats {
7+
public static final double SUPPLY_VOLTAGE = 12;
48
private static boolean IS_SIMULATION = false;
59
private static boolean IS_REPLAY = false;
610
private static double PERIODIC_TIME_SECONDS = 0.02;
711

12+
/**
13+
* Sets the current robot stats. This should be called in the robot's init method.
14+
* If isReal is true both simulation and replay will be false, otherwise they will be set according to the replay type.
15+
* We use this structure to avoid using static variables in the Robot class.
16+
*
17+
* @param isReal whether the robot is real or a simulation. This should be taken from the Robot class
18+
* @param replayType the type of replay
19+
*/
820
public static void setCurrentRobotStats(boolean isReal, ReplayType replayType) {
921
if (isReal || replayType.equals(ReplayType.NONE)) {
1022
IS_SIMULATION = !isReal;
1123
IS_REPLAY = false;
1224
return;
1325
}
14-
26+
1527
IS_SIMULATION = replayType.equals(ReplayType.SIMULATION_REPLAY);
1628
IS_REPLAY = true;
1729
}
1830

31+
/**
32+
* Sets how frequently the simulation is updated.
33+
*
34+
* @param periodicTimeSeconds the periodic time in seconds
35+
*/
1936
public static void setPeriodicTimeSeconds(double periodicTimeSeconds) {
2037
PERIODIC_TIME_SECONDS = periodicTimeSeconds;
2138
}
2239

40+
/**
41+
* @return the periodic time in seconds set in {@link #setPeriodicTimeSeconds(double)}
42+
*/
2343
public static double getPeriodicTimeSeconds() {
2444
return PERIODIC_TIME_SECONDS;
2545
}
2646

47+
/**
48+
* @return whether the robot is in replay mode or not
49+
*/
2750
public static boolean isReplay() {
2851
return IS_REPLAY;
2952
}
3053

54+
/**
55+
* @return whether the robot is running in simulation or not
56+
*/
3157
public static boolean isSimulation() {
3258
return IS_SIMULATION;
3359
}
3460

61+
/**
62+
* An enum that represents the type of replay.
63+
*/
3564
public enum ReplayType {
65+
/**
66+
* The robot is not in replay mode
67+
*/
3668
NONE,
69+
/**
70+
* The robot is in simulation replay mode
71+
*/
3772
SIMULATION_REPLAY,
73+
/**
74+
* The robot is in real replay mode
75+
*/
3876
REAL_REPLAY
3977
}
4078
}

src/main/java/org/trigon/hardware/SignalThreadBase.java

Lines changed: 29 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,21 +7,41 @@
77
import java.util.concurrent.ArrayBlockingQueue;
88
import java.util.concurrent.locks.ReentrantLock;
99

10+
/**
11+
* A class that represents a base for a signal thread.
12+
* Signal threads are specialized threads that run at a specific frequency to handle updating signals.
13+
*/
1014
public class SignalThreadBase extends Thread {
1115
public static final ReentrantLock SIGNALS_LOCK = new ReentrantLock();
1216
protected final Queue<Double> timestamps = new ArrayBlockingQueue<>(100);
1317
private final ThreadInputsAutoLogged threadInputs = new ThreadInputsAutoLogged();
1418
private final String name;
15-
protected double odometryFrequencyHertz = 50;
19+
protected double threadFrequencyHertz = 50;
1620

21+
/**
22+
* Creates a new SignalThreadBase.
23+
*
24+
* @param name the name of the thread
25+
*/
1726
public SignalThreadBase(String name) {
1827
this.name = name;
1928
}
2029

21-
public void setOdometryFrequencyHertz(double odometryFrequencyHertz) {
22-
this.odometryFrequencyHertz = odometryFrequencyHertz;
30+
/**
31+
* Sets the thread frequency in hertz.
32+
* The thread frequency determines how often the robot's position and motion data are updated.
33+
* A higher frequency will result in more frequent updates, but may also demand more processing power.
34+
* Only used for Spark motors.
35+
*
36+
* @param threadFrequencyHertz the odometry frequency in hertz
37+
*/
38+
public void setThreadFrequencyHertz(double threadFrequencyHertz) {
39+
this.threadFrequencyHertz = threadFrequencyHertz;
2340
}
2441

42+
/**
43+
* Updates the latest timestamps, and processes the inputs.
44+
*/
2545
public void updateLatestTimestamps() {
2646
if (!RobotHardwareStats.isReplay()) {
2747
threadInputs.timestamps = timestamps.stream().mapToDouble(Double::doubleValue).toArray();
@@ -30,6 +50,11 @@ public void updateLatestTimestamps() {
3050
Logger.processInputs(name, threadInputs);
3151
}
3252

53+
/**
54+
* Gets the latest timestamps when signals were updated.
55+
*
56+
* @return the latest timestamps
57+
*/
3358
public double[] getLatestTimestamps() {
3459
return threadInputs.timestamps;
3560
}
@@ -38,4 +63,4 @@ public double[] getLatestTimestamps() {
3863
public static class ThreadInputs {
3964
public double[] timestamps;
4065
}
41-
}
66+
}

src/main/java/org/trigon/hardware/SignalUtilities.java

Lines changed: 0 additions & 32 deletions
This file was deleted.

src/main/java/org/trigon/hardware/misc/KeyboardController.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,9 @@
33
import edu.wpi.first.wpilibj2.command.button.Trigger;
44
import org.littletonrobotics.junction.networktables.LoggedDashboardBoolean;
55

6+
/**
7+
* A class that represents a keyboard controller. Used to get input from a keyboard.
8+
*/
69
public class KeyboardController {
710
private final LoggedDashboardBoolean
811
esc, f1, f2, f3, f4, f5, f6, f7, f8, f9, f10,

src/main/java/org/trigon/hardware/misc/XboxController.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55
import edu.wpi.first.wpilibj2.command.WaitCommand;
66
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
77

8+
/**
9+
* A class that represents an Xbox controller. Used to get the values of the sticks and buttons on a controller, with the option of a deadband and exponentiation.
10+
*/
811
public class XboxController extends CommandXboxController {
912
private int exponent = 1;
1013
private double deadband = 0;

src/main/java/org/trigon/hardware/misc/leds/AddressableLEDStrip.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -152,13 +152,13 @@ void rainbow(double brightness, double speed, boolean inverted) {
152152
@Override
153153
void sectionColor(Supplier<Color>[] colors) {
154154
final int amountOfSections = colors.length;
155-
final int LEDsPerSection = (int) Math.floor(numberOfLEDs / amountOfSections);
155+
final int ledsPerSection = (int) Math.floor(numberOfLEDs / amountOfSections);
156156

157157
for (int i = 0; i < amountOfSections; i++)
158158
setLEDColors(
159159
inverted ? colors[amountOfSections - i - 1].get() : colors[i].get(),
160-
LEDsPerSection * i,
161-
i == amountOfSections - 1 ? numberOfLEDs - 1 : LEDsPerSection * (i + 1) - 1
160+
ledsPerSection * i,
161+
i == amountOfSections - 1 ? numberOfLEDs - 1 : ledsPerSection * (i + 1) - 1
162162
);
163163
}
164164

@@ -186,7 +186,7 @@ private void setBreathingLEDs(Color color, int breathingLEDs, LarsonAnimation.Bo
186186
for (int i = 0; i < breathingLEDs; i++) {
187187
if (lastBreatheLED - i >= indexOffset && lastBreatheLED - i < indexOffset + numberOfLEDs)
188188
LED_BUFFER.setLED(lastBreatheLED - i, color);
189-
189+
190190
else if (lastBreatheLED - i < indexOffset + numberOfLEDs) {
191191
if (bounceMode.equals(LarsonAnimation.BounceMode.Back) || bounceMode.equals(LarsonAnimation.BounceMode.Center) && i > breathingLEDs / 2)
192192
return;

src/main/java/org/trigon/hardware/misc/leds/CANdleLEDStrip.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,8 @@ public class CANdleLEDStrip extends LEDStrip {
1515
private final int animationSlot;
1616

1717
/**
18-
* Sets the CANdle instance to be used for controlling the LED strips. Must be set before using any LED strips. Should only be called once
18+
* Sets the CANdle instance to be used for controlling the LED strips. Must be set before using any LED strips. Should only be called once.
19+
* Must be configured before being set.
1920
*
2021
* @param candle the CANdle instance to be used
2122
*/
@@ -140,19 +141,19 @@ void rainbow(double brightness, double speed, boolean inverted) {
140141

141142
@Override
142143
void sectionColor(Supplier<Color>[] colors) {
143-
final int LEDSPerSection = (int) Math.floor(numberOfLEDs / colors.length);
144-
setSectionColor(colors.length, LEDSPerSection, colors);
144+
final int ledsPerSection = (int) Math.floor(numberOfLEDs / colors.length);
145+
setSectionColor(colors.length, ledsPerSection, colors);
145146
}
146147

147-
private void setSectionColor(int amountOfSections, int LEDSPerSection, Supplier<Color>[] colors) {
148+
private void setSectionColor(int amountOfSections, int ledsPerSection, Supplier<Color>[] colors) {
148149
for (int i = 0; i < amountOfSections; i++) {
149150
CANDLE.setLEDs(
150151
(int) (inverted ? colors[amountOfSections - i - 1].get().red : colors[i].get().red),
151152
(int) (inverted ? colors[amountOfSections - i - 1].get().green : colors[i].get().green),
152153
(int) (inverted ? colors[amountOfSections - i - 1].get().blue : colors[i].get().blue),
153154
0,
154-
LEDSPerSection * i + indexOffset,
155-
i == amountOfSections - 1 ? numberOfLEDs - 1 : LEDSPerSection * (i + 1) - 1
155+
ledsPerSection * i + indexOffset,
156+
i == amountOfSections - 1 ? numberOfLEDs - 1 : ledsPerSection * (i + 1) - 1
156157
);
157158
}
158159
}

0 commit comments

Comments
 (0)