Skip to content
Merged
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
14 changes: 14 additions & 0 deletions src/main/java/com/team1816/lib/util/BaseShooterCalculator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package com.team1816.lib.util;

import com.team1816.lib.BaseRobotState;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;

public abstract class BaseShooterCalculator implements IShooterCalculator {
public Rotation2d getTurretAngle(Translation2d shooter, Translation2d target, boolean useChassisSpeedForHoodAngleAndSpeed) {
Translation2d shooterToTargetTranslation2d = target.minus(shooter);
Rotation2d fieldRelativeRotation2dToTarget = shooterToTargetTranslation2d.getAngle();
Rotation2d robotRotation2d = BaseRobotState.robotPose.getRotation();
return fieldRelativeRotation2dToTarget.minus(robotRotation2d);
}
}
12 changes: 12 additions & 0 deletions src/main/java/com/team1816/lib/util/IShooterCalculator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
package com.team1816.lib.util;

import com.team1816.lib.BaseRobotState;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;

public interface IShooterCalculator {
Rotation2d getTurretAngle(Translation2d turret, Translation2d target, boolean useChassisSpeedForHoodAngleAndSpeed);
ShooterCalculatorResponse getShooterSettings(Translation2d turret, Translation2d target, boolean useChassisSpeedForHoodAngleAndSpeed);

record ShooterCalculatorResponse(double inclineAngleRotations, double launchVelocityRPS) {}
}
43 changes: 34 additions & 9 deletions src/main/java/com/team1816/lib/util/ShooterTableCalculator.java
Original file line number Diff line number Diff line change
@@ -1,21 +1,30 @@
package com.team1816.lib.util;

import com.team1816.lib.BaseRobotState;
import com.team1816.lib.hardware.ShooterSettingsConfig;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import org.apache.commons.math3.analysis.interpolation.LinearInterpolator;
import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction;

import java.util.List;

import static com.team1816.lib.Singleton.factory;

public class ShooterTableCalculator {
public class ShooterTableCalculator extends BaseShooterCalculator {

private final ShotLookup shotLookup;
private final PolynomialSplineFunction inclineAngleRotationsFunction, launchVelocityRPSFunction;

public ShooterTableCalculator() {
ShooterSettingsConfig shooterSettings = factory.getShooterSettingsConfig();

List<Double> distancesInches = shooterSettings.distancesInches;
List<Double> inclineAnglesRotations = shooterSettings.inclineAnglesRotations;
List<Double> launchVelocitiesRPS = shooterSettings.launchVelocitiesRPS;
LinearInterpolator inclineAngleRotationsLI = new LinearInterpolator();
LinearInterpolator launchVelocityRPSLI = new LinearInterpolator();

double[] distancesInchesArray = distancesInches.stream()
.mapToDouble(Double::doubleValue)
Expand All @@ -27,15 +36,31 @@ public ShooterTableCalculator() {
.mapToDouble(Double::doubleValue)
.toArray();

shotLookup = new ShotLookup(distancesInchesArray, inclineAnglesRotationsArray, launchVelocitiesRPSArray);
this.inclineAngleRotationsFunction = inclineAngleRotationsLI.interpolate(distancesInchesArray, inclineAnglesRotationsArray);
this.launchVelocityRPSFunction = launchVelocityRPSLI.interpolate(distancesInchesArray, launchVelocitiesRPSArray);
}

public ShooterDistanceSetting getShooterDistanceSetting(double distanceInches) {
return new ShooterDistanceSetting(
shotLookup.getInclineAngleRotations(distanceInches),
shotLookup.getLaunchVelocityRPS(distanceInches)
);
public ShooterCalculatorResponse getShooterSettings(Translation2d shooter, Translation2d target, boolean useChassisSpeedForHoodAngleAndSpeed) {
double distanceToTargetMeters = shooter.getDistance(target);
double distanceToTargetInches = Units.metersToInches(distanceToTargetMeters);
double inclineAngleRotations = getInclineAngleRotations(distanceToTargetInches);
double inclineAngleDegrees = Units.rotationsToDegrees(inclineAngleRotations);
double launchVelocityRPS = getLaunchVelocityRPS(distanceToTargetInches);

return new ShooterCalculatorResponse(inclineAngleDegrees, launchVelocityRPS);
}

private double getInclineAngleRotations(double distanceInches) {
var knots = inclineAngleRotationsFunction.getKnots();
// Clamp the distance to within the interpolation range.
double clampedDistanceInches = MathUtil.clamp(distanceInches, knots[0], knots[knots.length - 1]);
return inclineAngleRotationsFunction.value(clampedDistanceInches);
}

public record ShooterDistanceSetting(double inclineAngleRotations, double launchVelocityRPS) {}
private double getLaunchVelocityRPS(double distanceInches) {
var knots = launchVelocityRPSFunction.getKnots();
// Clamp the distance to within the interpolation range.
double clampedDistanceInches = MathUtil.clamp(distanceInches, knots[0], knots[knots.length - 1]);
return launchVelocityRPSFunction.value(clampedDistanceInches);
}
}
30 changes: 0 additions & 30 deletions src/main/java/com/team1816/lib/util/ShotLookup.java

This file was deleted.

25 changes: 10 additions & 15 deletions src/main/java/com/team1816/season/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import com.team1816.lib.subsystems.ITestableSubsystem;
import com.team1816.lib.util.FieldContainer;
import com.team1816.lib.util.GreenLogger;
import com.team1816.lib.util.IShooterCalculator;
import com.team1816.lib.util.ShooterTableCalculator;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.*;
Expand Down Expand Up @@ -84,6 +85,8 @@ public class Shooter extends SubsystemBase implements ITestableSubsystem {
*/
private double turretAngleAdjustmentDegrees = 0;

private boolean useChassisSpeedForHoodAngleAndSpeed = false;

//MOTORS
private final IMotor topLaunchMotor = (IMotor) factory.getDevice(NAME, "topLaunchMotor");
private final IMotor bottomLaunchMotor = (IMotor) factory.getDevice(NAME, "bottomLaunchMotor");
Expand Down Expand Up @@ -498,11 +501,8 @@ private Translation2d flipTranslation2dBasedOnAlliance(Translation2d blueTransla
* @param targetTranslation2d The {@link Translation2d} of the target to aim at.
*/
private void aimTurretAtTarget(Translation2d targetTranslation2d) {
Translation2d shooterTranslation2d = getCurrentTurretPose2d().getTranslation();
Translation2d shooterToTargetTranslation2d = targetTranslation2d.minus(shooterTranslation2d);
Rotation2d fieldRelativeRotation2dToTarget = shooterToTargetTranslation2d.getAngle();
Rotation2d robotRotation2d = BaseRobotState.robotPose.getRotation();
Rotation2d robotRelativeRotation2dToTarget = fieldRelativeRotation2dToTarget.minus(robotRotation2d);
Rotation2d robotRelativeRotation2dToTarget = shooterTableCalculator.getTurretAngle(getCurrentTurretPose2d().getTranslation(),
targetTranslation2d, useChassisSpeedForHoodAngleAndSpeed);
double robotRelativeDegreesToTarget = robotRelativeRotation2dToTarget.getDegrees();
setTurretAngle(robotRelativeDegreesToTarget);
}
Expand All @@ -514,16 +514,11 @@ private void aimTurretAtTarget(Translation2d targetTranslation2d) {
* @param targetTranslation2d The {@link Translation2d} of the target to aim at.
*/
private void aimInclineAndLaunchersAtTarget(Translation2d targetTranslation2d) {
Translation2d shooterTranslation2d = getCurrentTurretPose2d().getTranslation();
double distanceToTargetMeters = shooterTranslation2d.getDistance(targetTranslation2d);
double distanceToTargetInches = Units.metersToInches(distanceToTargetMeters);
ShooterTableCalculator.ShooterDistanceSetting shooterDistanceSetting = shooterTableCalculator
.getShooterDistanceSetting(distanceToTargetInches);
double inclineAngleRotations = shooterDistanceSetting.inclineAngleRotations();
double inclineAngleDegrees = Units.rotationsToDegrees(inclineAngleRotations);
double launchVelocityRPS = shooterDistanceSetting.launchVelocityRPS();
setInclineAngle(inclineAngleDegrees);
setLaunchVelocities(launchVelocityRPS);
IShooterCalculator.ShooterCalculatorResponse response = shooterTableCalculator.getShooterSettings(getCurrentTurretPose2d().getTranslation(),
targetTranslation2d, useChassisSpeedForHoodAngleAndSpeed);

setInclineAngle(response.inclineAngleRotations());
setLaunchVelocities(response.launchVelocityRPS());
}

/**
Expand Down
Loading