Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Command Changes #18

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 42 additions & 14 deletions src/main/java/org/trigon/commands/GearRatioCalculationCommand.java
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
package org.trigon.commands;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.*;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardBoolean;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

import java.util.function.DoubleConsumer;
import java.util.function.DoubleSupplier;

public class GearRatioCalculationCommand extends Command {
public class GearRatioCalculationCommand extends SequentialCommandGroup {
private final DoubleSupplier rotorPositionSupplier;
private final DoubleSupplier encoderPositionSupplier;
private final DoubleConsumer runGearRatioCalculation;
private final String subsystemName;
private final double backlashAccountabilityTimeSeconds;

private final LoggedDashboardNumber movementVoltage;
private final LoggedDashboardBoolean shouldMoveClockwise;
Expand All @@ -22,39 +22,67 @@ public class GearRatioCalculationCommand extends Command {
private double startingEncoderPosition;
private double gearRatio;

public GearRatioCalculationCommand(DoubleSupplier rotorPositionSupplier, DoubleSupplier encoderPositionSupplier, DoubleConsumer runGearRatioCalculation, SubsystemBase requirement) {
public GearRatioCalculationCommand(
DoubleSupplier rotorPositionSupplier,
DoubleSupplier encoderPositionSupplier,
DoubleConsumer runGearRatioCalculation,
double backlashAccountabilityTimeSeconds,
SubsystemBase requirement
) {
this.rotorPositionSupplier = rotorPositionSupplier;
this.encoderPositionSupplier = encoderPositionSupplier;
this.runGearRatioCalculation = runGearRatioCalculation;
this.subsystemName = requirement.getName();
this.backlashAccountabilityTimeSeconds = backlashAccountabilityTimeSeconds;

this.movementVoltage = new LoggedDashboardNumber("GearRatioCalculation/" + this.subsystemName + "/Voltage", 1);
this.shouldMoveClockwise = new LoggedDashboardBoolean("GearRatioCalculation/" + this.subsystemName + "/ShouldMoveClockwise", false);

addRequirements(requirement);
addCommands(
getGearRatioCalculationCommand(),
getBacklashAccountabilityCommand(),
getLogGearRatioCommand()
);
}

@Override
public void initialize() {
private Command getBacklashAccountabilityCommand() {
Nummun14 marked this conversation as resolved.
Show resolved Hide resolved
return new WaitCommand(backlashAccountabilityTimeSeconds);
}

private Command getGearRatioCalculationCommand() {
return new InitExecuteCommand(
this::getStartingPositions,
this::runGearRatioCalculation
);
}

private Command getLogGearRatioCommand() {
return new InstantCommand(
() -> {
logGearRatio();
printResult();
}
);
}

private void getStartingPositions() {
startingRotorPosition = rotorPositionSupplier.getAsDouble();
startingEncoderPosition = encoderPositionSupplier.getAsDouble();
}

@Override
public void execute() {
private void runGearRatioCalculation() {
runGearRatioCalculation.accept(movementVoltage.get() * getRotationDirection());
gearRatio = calculateGearRatio();
}

private void logGearRatio() {

Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/RotorDistance", getRotorDistance());
Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/EncoderDistance", getEncoderDistance());
Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/GearRatio", gearRatio);
}

@Override
public void end(boolean interrupted) {
printResult();
}

private double calculateGearRatio() {
final double currentRotorPosition = getRotorDistance();
final double currentEncoderPosition = getEncoderDistance();
Expand All @@ -76,4 +104,4 @@ private int getRotationDirection() {
private void printResult() {
System.out.println(subsystemName + " Gear Ratio: " + gearRatio);
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ public class WheelRadiusCharacterizationCommand extends Command {
private static final LoggedDashboardNumber ROTATION_RATE_LIMIT = new LoggedDashboardNumber("WheelRadiusCharacterization/RotationRateLimit", 1);
private static final LoggedDashboardBoolean SHOULD_MOVE_CLOCKWISE = new LoggedDashboardBoolean("WheelRadiusCharacterization/ShouldMoveClockwise", false);

private final double[] wheelDistancesFromCenterMeters;
private final double[]
wheelDistancesFromCenterMeters,
driveWheelRadii;
private final Supplier<double[]> wheelPositionsRadiansSupplier;
private final DoubleSupplier gyroYawRadiansSupplier;
private final DoubleConsumer runWheelRadiusCharacterization;
Expand All @@ -34,25 +36,32 @@ public class WheelRadiusCharacterizationCommand extends Command {
private double startingGyroYawRadians;
private double accumulatedGyroYawRadians;
private double[] startingWheelPositions;
private double driveWheelsRadius;

public WheelRadiusCharacterizationCommand(Translation2d[] wheelDistancesFromCenterMeters, Supplier<double[]> wheelPositionsRadiansSupplier,
DoubleSupplier gyroYawRadiansSupplier, DoubleConsumer runWheelRadiusCharacterization, SubsystemBase requirement
public WheelRadiusCharacterizationCommand(Translation2d[] wheelDistancesFromCenterMeters,
Supplier<double[]> wheelPositionsRadiansSupplier,
DoubleSupplier gyroYawRadiansSupplier,
DoubleConsumer runWheelRadiusCharacterization,
SubsystemBase requirement
) {
this.wheelDistancesFromCenterMeters = Arrays.stream(wheelDistancesFromCenterMeters).mapToDouble(Translation2d::getNorm).toArray();
this.wheelPositionsRadiansSupplier = wheelPositionsRadiansSupplier;
this.gyroYawRadiansSupplier = gyroYawRadiansSupplier;
this.runWheelRadiusCharacterization = runWheelRadiusCharacterization;
this.driveWheelRadii = new double[wheelDistancesFromCenterMeters.length];
addRequirements(requirement);
}

public WheelRadiusCharacterizationCommand(double[] wheelDistancesFromCenterMeters, Supplier<double[]> wheelPositionsRadiansSupplier,
DoubleSupplier gyroYawRadiansSupplier, DoubleConsumer runWheelRadiusCharacterization, SubsystemBase requirement
public WheelRadiusCharacterizationCommand(double[] wheelDistancesFromCenterMeters,
Supplier<double[]> wheelPositionsRadiansSupplier,
DoubleSupplier gyroYawRadiansSupplier,
DoubleConsumer runWheelRadiusCharacterization,
SubsystemBase requirement
) {
this.wheelDistancesFromCenterMeters = wheelDistancesFromCenterMeters;
this.wheelPositionsRadiansSupplier = wheelPositionsRadiansSupplier;
this.gyroYawRadiansSupplier = gyroYawRadiansSupplier;
this.runWheelRadiusCharacterization = runWheelRadiusCharacterization;
this.driveWheelRadii = new double[wheelDistancesFromCenterMeters.length];
addRequirements(requirement);
}

Expand All @@ -66,10 +75,10 @@ public void execute() {
driveMotors();

accumulatedGyroYawRadians = getAccumulatedGyroYaw();
driveWheelsRadius = calculateDriveWheelRadius();
calculateDriveWheelRadius();

Logger.recordOutput("WheelRadiusCharacterization/AccumulatedGyroYawRadians", accumulatedGyroYawRadians);
Logger.recordOutput("RadiusCharacterization/DriveWheelRadius", driveWheelsRadius);
logWheelRadii();
}

@Override
Expand All @@ -94,24 +103,28 @@ private double getAccumulatedGyroYaw() {
return Math.abs(startingGyroYawRadians - gyroYawRadiansSupplier.getAsDouble());
}

private double calculateDriveWheelRadius() {
driveWheelsRadius = 0;
private void calculateDriveWheelRadius() {
final double[] wheelPositionsRadians = wheelPositionsRadiansSupplier.get();

for (int i = 0; i < 4; i++) {
final double accumulatedWheelRadians = Math.abs(wheelPositionsRadians[i] - startingWheelPositions[i]);
driveWheelsRadius += (accumulatedGyroYawRadians * wheelDistancesFromCenterMeters[i]) / accumulatedWheelRadians;
Logger.recordOutput("RadiusCharacterization/AccumulatedWheelRadians" + i, accumulatedWheelRadians);
driveWheelRadii[i] = (accumulatedGyroYawRadians * wheelDistancesFromCenterMeters[i]) / accumulatedWheelRadians;
Logger.recordOutput("RadiusCharacterization/AccumulatedWheelRadians" + i, driveWheelRadii[i]);
}

return driveWheelsRadius /= 4;
}

private void printResults() {
if (accumulatedGyroYawRadians <= Math.PI * 2.0)
if (accumulatedGyroYawRadians <= Math.PI * 2.0) {
System.out.println("Not enough data for characterization");
else
System.out.println("Drive Wheel Radius: " + driveWheelsRadius + " meters");
return;
}
for (int i = 0; i < driveWheelRadii.length; i++)
System.out.println("Drive Wheel Radius for Module " + i + ": " + driveWheelRadii[i] + " meters");
}

private void logWheelRadii() {
for (int i = 0; i < driveWheelRadii.length; i++)
Logger.recordOutput("RadiusCharacterization/DriveWheelRadiusModule" + i, driveWheelRadii[i]);
}

private int getRotationDirection() {
Expand Down
Loading