A bunch of changes, mostly related to shooting balls at the hub dynamically, still need a means of doing this based on a single apriltag, in the event the robot pose is unreliable

This commit is contained in:
2026-02-12 16:02:08 -05:00
parent f8429dc899
commit 91a5281202
12 changed files with 181 additions and 135 deletions

View File

@@ -4,6 +4,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.util.Units;
public class CompetitionConstants {
@@ -14,6 +15,11 @@ public class CompetitionConstants {
AprilTagFields.kDefaultField
);
public static final double kHubGoalHeightMeters = Units.inchesToMeters(72);
// TODO Real Values
public static final Transform3d KRobotToShooter = new Transform3d();
public static final Pose2d kBlueHubLocation = new Pose2d(
Units.inchesToMeters(182.11),
Units.inchesToMeters(158.84),

View File

@@ -4,6 +4,8 @@ import com.revrobotics.spark.FeedbackSensor;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap;
public class HoodConstants {
// TODO Real Values
public static final int kMotorCANID = 0;
@@ -15,13 +17,18 @@ public class HoodConstants {
public static final double kV = 0;
public static final double kA = 0;
public static final double kStartupAngle = 0;
public static final double kMaxManualSpeedMultiplier = .5;
public static final int kCurrentLimit = 15;
public static final boolean kInverted = false;
public static final boolean kUseInterpolatorForAngle = false;
public static final IdleMode kIdleMode = IdleMode.kBrake;
// TODO This needs to be filled in from some source
public static final InterpolatingDoubleTreeMap kDistanceToAngle = new InterpolatingDoubleTreeMap();
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A CONFIGURATION ITEM
public static final SparkMaxConfig kConfig = new SparkMaxConfig();

View File

@@ -21,9 +21,10 @@ public class IntakePivotConstants {
}
public static final int kLeftMotorCANID = 0;
public static final int kRightMotorCANID = 1;
public static final int kRightMotorCANID = 0;
public static final double kConversionFactor = 0;
public static final double kMaxManualSpeedMultiplier = .5;
public static final double kP = 0;
public static final double kI = 0;

View File

@@ -8,23 +8,17 @@ import edu.wpi.first.math.util.Units;
public class ShooterConstants {
public enum ShooterSpeeds {
kHubSpeed(0, 0),
kFeedSpeed(0, 0);
kHubSpeed(0),
kFeedSpeed(0);
private double frontRollerMPS;
private double rearRollerMPS;
private double speedMPS;
private ShooterSpeeds(double frontRollerMPS, double rearRollerMPS) {
this.frontRollerMPS = frontRollerMPS;
this.rearRollerMPS = rearRollerMPS;
private ShooterSpeeds(double speedMPS) {
this.speedMPS = speedMPS;
}
public double getFrontRollerMPS() {
return frontRollerMPS;
}
public double getRearRollerMPS() {
return rearRollerMPS;
public double getSpeedMPS() {
return speedMPS;
}
}
@@ -33,29 +27,31 @@ public class ShooterConstants {
public static final double kWheelDiameter = Units.inchesToMeters(6);
// TODO Real values
public static final int kFrontShooterMotor1CANID = 0;
public static final int kFrontShooterMotor2CANID = 0;
public static final int kRearShooterMotor1CANID = 0;
public static final int kRearShooterMotor2CANID = 0;
public static final int kLeftShooterMotor1CANID = 0;
public static final int kLeftShooterMotor2CANID = 0;
public static final int kRightShooterMotor1CANID = 0;
public static final int kRightShooterMotor2CANID = 0;
public static final boolean kFrontShooterMotor1Inverted = false;
public static final boolean kFrontShooterMotor2Inverted = false;
public static final boolean kRearShooterMotor1Inverted = false;
public static final boolean kRearShooterMotor2Inverted = false;
public static final boolean kLeftShooterMotor1Inverted = false;
public static final boolean kLeftShooterMotor2Inverted = false;
public static final boolean kRightShooterMotor1Inverted = false;
public static final boolean kRightShooterMotor2Inverted = false;
public static final double kFrontP = 0;
public static final double kFrontI = 0;
public static final double kFrontD = 0;
public static final double kFrontS = 0;
public static final double kFrontV = 0;
public static final double kFrontA = 0;
public static final double kLeftP = 0;
public static final double kLeftI = 0;
public static final double kLeftD = 0;
public static final double kLeftS = 0;
public static final double kLeftV = 0;
public static final double kLeftA = 0;
public static final double kRearP = 0;
public static final double kRearI = 0;
public static final double kRearD = 0;
public static final double kRearS = 0;
public static final double kRearV = 0;
public static final double kRearA = 0;
public static final double kRightP = 0;
public static final double kRightI = 0;
public static final double kRightD = 0;
public static final double kRightS = 0;
public static final double kRightV = 0;
public static final double kRightA = 0;
public static final double kShooterHeightMeters = 0;
// TODO Is this value sane?
public static final int kCurrentLimit = 30;
@@ -64,51 +60,51 @@ public class ShooterConstants {
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A CONFIGURATION ITEM
public static final SparkMaxConfig kFrontMotor1Config = new SparkMaxConfig();
public static final SparkMaxConfig kFrontMotor2Config = new SparkMaxConfig();
public static final SparkMaxConfig kRearMotor1Config = new SparkMaxConfig();
public static final SparkMaxConfig kRearMotor2Config = new SparkMaxConfig();
public static final SparkMaxConfig kLeftMotor1Config = new SparkMaxConfig();
public static final SparkMaxConfig kLeftMotor2Config = new SparkMaxConfig();
public static final SparkMaxConfig kRightMotor1Config = new SparkMaxConfig();
public static final SparkMaxConfig kRightMotor2Config = new SparkMaxConfig();
static {
kFrontMotor1Config
kLeftMotor1Config
.idleMode(kShooterIdleMode)
.smartCurrentLimit(kCurrentLimit)
.inverted(kFrontShooterMotor1Inverted);
kFrontMotor1Config.absoluteEncoder
.inverted(kLeftShooterMotor1Inverted);
kLeftMotor1Config.absoluteEncoder
.positionConversionFactor(kWheelDiameter * Math.PI)
.velocityConversionFactor(kWheelDiameter * Math.PI / 60);
kFrontMotor1Config.closedLoop
kLeftMotor1Config.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.pid(kFrontP, kFrontI, kFrontD)
.pid(kLeftP, kLeftI, kLeftD)
.outputRange(-1, 1)
.feedForward
.sva(kFrontS, kFrontV, kFrontA);
.sva(kLeftS, kLeftV, kLeftA);
kFrontMotor2Config
kLeftMotor2Config
.idleMode(kShooterIdleMode)
.smartCurrentLimit(kCurrentLimit)
.inverted(kFrontShooterMotor2Inverted)
.follow(kFrontShooterMotor1CANID);
.inverted(kLeftShooterMotor2Inverted)
.follow(kLeftShooterMotor1CANID);
kRearMotor1Config
kRightMotor1Config
.idleMode(kShooterIdleMode)
.smartCurrentLimit(kCurrentLimit)
.inverted(kRearShooterMotor1Inverted);
kRearMotor1Config.absoluteEncoder
.inverted(kRightShooterMotor1Inverted);
kRightMotor1Config.absoluteEncoder
.positionConversionFactor(kWheelDiameter * Math.PI)
.velocityConversionFactor(kWheelDiameter * Math.PI / 60);
kRearMotor1Config.closedLoop
kRightMotor1Config.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
.pid(kRearP, kRearI, kRearD)
.pid(kRightP, kRightI, kRightD)
.outputRange(-1, 1)
.feedForward
.sva(kRearS, kRearV, kRearA);
.sva(kRightS, kRightV, kRightA);
kRearMotor2Config
kRightMotor2Config
.idleMode(kShooterIdleMode)
.smartCurrentLimit(kCurrentLimit)
.inverted(kRearShooterMotor2Inverted)
.follow(kRearShooterMotor1CANID);
.inverted(kRightShooterMotor2Inverted)
.follow(kRightShooterMotor1CANID);
}
}