Skip to content

Commit 74e963f

Browse files
authored
General Update (#22)
* updated akit stuff, and added more gear ratio calc constructors * Realized some of these constructors are really unnecacery * this bugged me * made spark sim more efficiant, and removed usage of deprecated methods * added jdocs, and corrected cf in spark sim * jdoc changes * name change
1 parent 6a3fb40 commit 74e963f

File tree

7 files changed

+74
-31
lines changed

7 files changed

+74
-31
lines changed

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

Lines changed: 39 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
import edu.wpi.first.wpilibj2.command.Command;
66
import edu.wpi.first.wpilibj2.command.SubsystemBase;
77
import org.littletonrobotics.junction.Logger;
8-
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
8+
import org.littletonrobotics.junction.networktables.LoggedNetworkNumber;
99
import org.trigon.hardware.phoenix6.cancoder.CANcoderEncoder;
1010
import org.trigon.hardware.phoenix6.cancoder.CANcoderSignal;
1111
import org.trigon.hardware.phoenix6.talonfx.TalonFXMotor;
@@ -23,14 +23,29 @@ public class GearRatioCalculationCommand extends Command {
2323
private final DoubleConsumer runGearRatioCalculation;
2424
private final String subsystemName;
2525
private final double backlashAccountabilityTimeSeconds;
26-
private final LoggedDashboardNumber movementVoltage;
26+
private final LoggedNetworkNumber movementVoltage;
2727

2828
private double startingRotorPosition;
2929
private double startingEncoderPosition;
3030
private double gearRatio;
3131
private double startTime;
3232
private boolean hasSetStartingPositions = false;
3333

34+
/**
35+
* Creates a new GearRatioCalculationCommand.
36+
* This constructor takes a motor to run the gear ratio calculation on, and to measure the distance the rotor travels.
37+
* It also takes an encoder to measure the distance traveled.
38+
* This constructor will record the starting positions without any delay. This might be problematic when the subsystem has backlash.
39+
* When you have backlash and want to account for it with a measuring delay, use {@link GearRatioCalculationCommand#GearRatioCalculationCommand(TalonFXMotor, CANcoderEncoder, double, SubsystemBase)}.
40+
*
41+
* @param motor the motor that drives the rotor
42+
* @param encoder the encoder that measures the distance traveled
43+
* @param requirement the subsystem that this command requires
44+
*/
45+
public GearRatioCalculationCommand(TalonFXMotor motor, CANcoderEncoder encoder, SubsystemBase requirement) {
46+
this(motor, encoder, 0, requirement);
47+
}
48+
3449
/**
3550
* Creates a new GearRatioCalculationCommand.
3651
* This constructor takes a motor to run the gear ratio calculation on, and to measure the distance the rotor travels.
@@ -51,11 +66,29 @@ public GearRatioCalculationCommand(TalonFXMotor motor, CANcoderEncoder encoder,
5166
);
5267
}
5368

69+
/**
70+
* Creates a new GearRatioCalculationCommand.
71+
* This constructor will record the starting positions without any delay. This might be problematic when the system has backlash.
72+
* When you have backlash and want to account for it with a measuring delay, use {@link GearRatioCalculationCommand#GearRatioCalculationCommand(DoubleSupplier, DoubleSupplier, DoubleConsumer, double, SubsystemBase)}.
73+
*
74+
* @param rotorPositionSupplier a supplier that returns the current position of the rotor. Must be in the same units as the encoder position supplier
75+
* @param encoderPositionSupplier a supplier that returns the current position of the encoder. Must be in the same units as the rotor position supplier
76+
* @param runGearRatioCalculation a consumer that drives the motor with a given voltage
77+
* @param requirement the subsystem that this command requires
78+
*/
79+
public GearRatioCalculationCommand(
80+
DoubleSupplier rotorPositionSupplier,
81+
DoubleSupplier encoderPositionSupplier,
82+
DoubleConsumer runGearRatioCalculation,
83+
SubsystemBase requirement) {
84+
this(rotorPositionSupplier, encoderPositionSupplier, runGearRatioCalculation, 0, requirement);
85+
}
86+
5487
/**
5588
* Creates a new GearRatioCalculationCommand.
5689
*
57-
* @param rotorPositionSupplier a supplier that returns the current position of the rotor in degrees
58-
* @param encoderPositionSupplier a supplier that returns the current position of the encoder in degrees
90+
* @param rotorPositionSupplier a supplier that returns the current position of the rotor. Must be in the same units as the encoder position supplier
91+
* @param encoderPositionSupplier a supplier that returns the current position of the encoder. Must be in the same units as the rotor position supplier
5992
* @param runGearRatioCalculation a consumer that drives the motor with a given voltage
6093
* @param backlashAccountabilityTimeSeconds the time to wait before setting the starting positions in order to account for backlash
6194
* @param requirement the subsystem that this command requires
@@ -72,7 +105,7 @@ public GearRatioCalculationCommand(
72105
this.subsystemName = requirement.getName();
73106
this.backlashAccountabilityTimeSeconds = backlashAccountabilityTimeSeconds;
74107

75-
this.movementVoltage = new LoggedDashboardNumber("GearRatioCalculation/" + this.subsystemName + "/Voltage", 1);
108+
this.movementVoltage = new LoggedNetworkNumber("GearRatioCalculation/" + this.subsystemName + "/Voltage", 1);
76109

77110
addRequirements(requirement);
78111
}
@@ -88,7 +121,7 @@ public void initialize() {
88121
public void execute() {
89122
runGearRatioCalculation();
90123

91-
if (Timer.getFPGATimestamp() - startTime > backlashAccountabilityTimeSeconds && !hasSetStartingPositions)
124+
if (Timer.getTimestamp() - startTime > backlashAccountabilityTimeSeconds && !hasSetStartingPositions)
92125
setStartingPositions();
93126

94127
if (hasSetStartingPositions) {

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
import edu.wpi.first.wpilibj2.command.Command;
44
import edu.wpi.first.wpilibj2.command.Subsystem;
5-
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
5+
import org.littletonrobotics.junction.networktables.LoggedNetworkNumber;
66

77
import java.util.Set;
88
import java.util.function.BiConsumer;
@@ -15,7 +15,7 @@
1515
*/
1616
public class NetworkTablesCommand extends Command {
1717
private final Consumer<Double[]> toRun;
18-
private final LoggedDashboardNumber[] dashboardNumbers;
18+
private final LoggedNetworkNumber[] dashboardNumbers;
1919
private final boolean runPeriodically;
2020

2121
/**
@@ -29,9 +29,9 @@ public class NetworkTablesCommand extends Command {
2929
public NetworkTablesCommand(Consumer<Double[]> toRun, boolean runPeriodically, Set<Subsystem> requirements, String... keys) {
3030
this.toRun = toRun;
3131
this.runPeriodically = runPeriodically;
32-
dashboardNumbers = new LoggedDashboardNumber[keys.length];
32+
dashboardNumbers = new LoggedNetworkNumber[keys.length];
3333
for (int i = 0; i < keys.length; i++)
34-
dashboardNumbers[i] = new LoggedDashboardNumber(keys[i]);
34+
dashboardNumbers[i] = new LoggedNetworkNumber(keys[i]);
3535
addRequirements(requirements.toArray(new Subsystem[0]));
3636
}
3737

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
import edu.wpi.first.wpilibj2.command.Command;
1313
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1414
import org.littletonrobotics.junction.Logger;
15-
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
15+
import org.littletonrobotics.junction.networktables.LoggedNetworkNumber;
1616

1717
import java.util.Arrays;
1818
import java.util.function.DoubleConsumer;
@@ -23,8 +23,8 @@
2323
* A command for characterizing the wheel radius of each module of a swerve drive system by calculating the radius of each drive wheel based on rotational data and robot yaw during operation.
2424
*/
2525
public class WheelRadiusCharacterizationCommand extends Command {
26-
private static final LoggedDashboardNumber CHARACTERIZATION_SPEED = new LoggedDashboardNumber("WheelRadiusCharacterization/SpeedRadiansPerSecond", 1);
27-
private static final LoggedDashboardNumber ROTATION_RATE_LIMIT = new LoggedDashboardNumber("WheelRadiusCharacterization/RotationRateLimit", 1);
26+
private static final LoggedNetworkNumber CHARACTERIZATION_SPEED = new LoggedNetworkNumber("WheelRadiusCharacterization/SpeedRadiansPerSecond", 1);
27+
private static final LoggedNetworkNumber ROTATION_RATE_LIMIT = new LoggedNetworkNumber("WheelRadiusCharacterization/RotationRateLimit", 1);
2828

2929
private final double[]
3030
wheelDistancesFromCenterMeters,

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ public double[] getThreadedSignal(String signalName) {
7373
}
7474

7575
private boolean shouldPrintError() {
76-
final double currentTime = Timer.getFPGATimestamp();
76+
final double currentTime = Timer.getTimestamp();
7777
final boolean shouldPrint = currentTime - lastErrorTimestamp > 5;
7878
if (shouldPrint)
7979
lastErrorTimestamp = currentTime;

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ void clearLEDColors() {
6565
@Override
6666
void blink(Color firstColor, double speed) {
6767
final double correctedSpeed = 1 - speed;
68-
final double currentTime = Timer.getFPGATimestamp();
68+
final double currentTime = Timer.getTimestamp();
6969

7070
if (currentTime - lastLEDAnimationChangeTime > correctedSpeed) {
7171
lastLEDAnimationChangeTime = currentTime;
@@ -89,7 +89,7 @@ void breathe(Color color, int breathingLEDs, double speed, boolean inverted, Lar
8989
clearLEDColors();
9090
final boolean correctedInverted = this.inverted != inverted;
9191
final double moveLEDTimeSeconds = 1 - speed;
92-
final double currentTime = Timer.getFPGATimestamp();
92+
final double currentTime = Timer.getTimestamp();
9393

9494
if (currentTime - lastLEDAnimationChangeTime > moveLEDTimeSeconds) {
9595
lastLEDAnimationChangeTime = currentTime;
@@ -108,7 +108,7 @@ void colorFlow(Color color, double speed, boolean inverted) {
108108
clearLEDColors();
109109
final boolean correctedInverted = this.inverted != inverted;
110110
final double moveLEDTimeSeconds = 1 - speed;
111-
final double currentTime = Timer.getFPGATimestamp();
111+
final double currentTime = Timer.getTimestamp();
112112

113113
if (currentTime - lastLEDAnimationChangeTime > moveLEDTimeSeconds) {
114114
lastLEDAnimationChangeTime = currentTime;
@@ -165,7 +165,7 @@ void sectionColor(Supplier<Color>[] colors) {
165165
@Override
166166
void resetLEDSettings() {
167167
lastBreatheLED = indexOffset;
168-
lastLEDAnimationChangeTime = Timer.getFPGATimestamp();
168+
lastLEDAnimationChangeTime = Timer.getTimestamp();
169169
rainbowFirstPixelHue = 0;
170170
isLEDAnimationChanged = false;
171171
amountOfColorFlowLEDs = 0;

src/main/java/org/trigon/hardware/rev/spark/io/RealSparkIO.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,9 @@ public void configure(SparkBaseConfig configuration, SparkBase.ResetMode resetMo
6666

6767
@Override
6868
public void setInverted(boolean inverted) {
69-
motor.setInverted(inverted);
69+
final SparkMaxConfig configuration = new SparkMaxConfig();
70+
configuration.inverted(inverted);
71+
motor.configure(configuration, SparkBase.ResetMode.kNoResetSafeParameters, SparkBase.PersistMode.kNoPersistParameters);
7072
}
7173

7274
@Override

src/main/java/org/trigon/hardware/rev/spark/io/SimulationSparkIO.java

Lines changed: 20 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,9 @@ public void setPeriodicFrameTimeout(int timeoutMs) {
7373

7474
@Override
7575
public void setInverted(boolean inverted) {
76-
motor.setInverted(inverted);
76+
final SparkMaxConfig configuration = new SparkMaxConfig();
77+
configuration.inverted(inverted);
78+
motor.configure(configuration, SparkBase.ResetMode.kNoResetSafeParameters, SparkBase.PersistMode.kNoPersistParameters);
7779
}
7880

7981
@Override
@@ -89,8 +91,9 @@ public void updateSimulation() {
8991
return;
9092

9193
updatePhysicsSimulation();
92-
updateMotorSimulation();
93-
updateEncoderSimulation();
94+
final double physicsSimulationVelocity = getPhysicsSimulationVelocity();
95+
updateMotorSimulation(physicsSimulationVelocity);
96+
updateEncoderSimulation(physicsSimulationVelocity);
9497
}
9598

9699
@Override
@@ -109,22 +112,27 @@ private void updatePhysicsSimulation() {
109112
physicsSimulation.updateMotor();
110113
}
111114

112-
private void updateMotorSimulation() {
113-
motorSimulation.iterate(getPhysicsSimulationVelocityForMotorSimulation(), RobotHardwareStats.SUPPLY_VOLTAGE, RobotHardwareStats.getPeriodicTimeSeconds());
115+
private void updateMotorSimulation(double physicsSimulationVelocityForSimulation) {
116+
motorSimulation.iterate(physicsSimulationVelocityForSimulation, RobotHardwareStats.SUPPLY_VOLTAGE, RobotHardwareStats.getPeriodicTimeSeconds());
114117
motorSimulation.setMotorCurrent(physicsSimulation.getCurrent());
115118
}
116119

117-
private void updateEncoderSimulation() {
118-
absoluteEncoderSimulation.iterate(getPhysicsSimulationVelocityForMotorSimulation(), RobotHardwareStats.getPeriodicTimeSeconds());
120+
private void updateEncoderSimulation(double physicsSimulationVelocityForSimulation) {
121+
absoluteEncoderSimulation.iterate(physicsSimulationVelocityForSimulation, RobotHardwareStats.getPeriodicTimeSeconds());
119122
}
120123

121-
private double getPhysicsSimulationVelocityForMotorSimulation() {
124+
/**
125+
* Gets the velocity from the physics simulation in the units set in the conversion factor. This is used in the iterate method to update the motor simulation.
126+
*
127+
* @return the velocity from the physics simulation
128+
*/
129+
private double getPhysicsSimulationVelocity() {
122130
if (isUsingAbsoluteEncoder)
123-
return getConversionFactor() * Conversions.perMinuteToPerSecond(physicsSimulation.getSystemVelocityRotationsPerSecond());
124-
return getConversionFactor() * Conversions.perMinuteToPerSecond(physicsSimulation.getRotorVelocityRotationsPerSecond());
131+
return getVelocityConversionFactor() * Conversions.perMinuteToPerSecond(physicsSimulation.getSystemVelocityRotationsPerSecond());
132+
return getVelocityConversionFactor() * Conversions.perMinuteToPerSecond(physicsSimulation.getRotorVelocityRotationsPerSecond());
125133
}
126134

127-
private double getConversionFactor() {
128-
return motor.configAccessor.encoder.getPositionConversionFactor();
135+
private double getVelocityConversionFactor() {
136+
return motor.configAccessor.encoder.getVelocityConversionFactor();
129137
}
130138
}

0 commit comments

Comments
 (0)