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
197 changes: 98 additions & 99 deletions src/main/deploy/choreo/DepottoLPreTrench.traj

Large diffs are not rendered by default.

236 changes: 125 additions & 111 deletions src/main/deploy/choreo/LBumpToLCleanup.traj

Large diffs are not rendered by default.

172 changes: 98 additions & 74 deletions src/main/deploy/choreo/LCleanupToLBump.traj

Large diffs are not rendered by default.

237 changes: 133 additions & 104 deletions src/main/deploy/choreo/LCleanuptoLPreTrench.traj

Large diffs are not rendered by default.

193 changes: 97 additions & 96 deletions src/main/deploy/choreo/LDisrupttoLPreTrench.traj

Large diffs are not rendered by default.

260 changes: 131 additions & 129 deletions src/main/deploy/choreo/LNeutraltoLPreTrench.traj

Large diffs are not rendered by default.

192 changes: 95 additions & 97 deletions src/main/deploy/choreo/LPreTrenchtoDepot.traj

Large diffs are not rendered by default.

198 changes: 107 additions & 91 deletions src/main/deploy/choreo/LPreTrenchtoLCleanup.traj

Large diffs are not rendered by default.

145 changes: 72 additions & 73 deletions src/main/deploy/choreo/LPreTrenchtoLClimb.traj

Large diffs are not rendered by default.

206 changes: 104 additions & 102 deletions src/main/deploy/choreo/LPreTrenchtoLNeutral.traj

Large diffs are not rendered by default.

12 changes: 6 additions & 6 deletions src/main/deploy/choreo/rebuiltChoreo.chor
Original file line number Diff line number Diff line change
Expand Up @@ -127,12 +127,12 @@
},
"LCleanup":{
"x":{
"exp":"6.068130016326904 m",
"val":6.068130016326904
"exp":"5.7387895584106445 m",
"val":5.7387895584106445
},
"y":{
"exp":"3.792367458343506 m",
"val":3.792367458343506
"exp":"3.73817777633667 m",
"val":3.73817777633667
},
"heading":{
"exp":"-90 deg",
Expand Down Expand Up @@ -169,8 +169,8 @@
},
"LPreTrench":{
"x":{
"exp":"3.3465769290924072 m",
"val":3.3465769290924072
"exp":"3.0828871726989746 m",
"val":3.0828871726989746
},
"y":{
"exp":"7.509117603302002 m",
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -765,8 +765,8 @@ public Command getLeftBumpDoubleDipAuto() {
Path.StartingLTrenchtoLNeutral,
Path.LNeutralToLBump,
Path.LBumptoLCleanup,
// Path.LCleanupToLBump
Path.EndWScoreLCleanuptoLPreTrench
Path.LCleanupToLBump
// Path.EndWScoreLCleanuptoLPreTrench
},
Commands.none());
}
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -946,6 +946,14 @@ public void robotPeriodic() {
.getTurretPose(swerve.getPose())
.getTranslation()
.getDistance(FieldUtils.getCurrentHubTranslation()));

Logger.recordOutput(
"AutoAim/Distance to feed target",
shooter
.getTurretPose(swerve.getPose())
.getTranslation()
.getDistance(
FeedTargets.getFeedTarget(Superstructure.getFeedTarget()).getTranslation()));
Logger.recordOutput(
"AutoAim/Feed Target", FeedTargets.getFeedTarget(Superstructure.getFeedTarget()).getPose());

Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/TurretIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.MotionMagicVoltage;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.Angle;
Expand Down Expand Up @@ -38,6 +39,7 @@ public static class TurretIOInputs {
private final StatusSignal<Temperature> tempC;

private MotionMagicVoltage motionMagic = new MotionMagicVoltage(0.0).withEnableFOC(true);
private PositionVoltage positionVoltage = new PositionVoltage(0.0).withEnableFOC(true);

// todo
private Rotation2d turretSetpoint = Rotation2d.kZero;
Expand Down Expand Up @@ -91,7 +93,8 @@ public void updateInputs(TurretIOInputs inputs) {

public void setTurretPosition(Rotation2d positionAngle) {
turretSetpoint = positionAngle;
motor.setControl(motionMagic.withPosition(positionAngle.getRotations()));
// motor.setControl(motionMagic.withPosition(positionAngle.getRotations()));
motor.setControl(positionVoltage.withPosition(positionAngle.getRotations()));
}

public void resetTurretEncoder(Rotation2d turretRotation) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -573,6 +573,8 @@ public static TalonFXConfiguration getTurretConfig() {
config.Slot0.kS = 0.45;
config.Slot0.kV = 5.7;
config.Slot0.kP = 240.0;
//kd was added once we switched to position voltage
config.Slot0.kD = 0.04;

config.MotionMagic.MotionMagicAcceleration = 10; // 2.064;
config.MotionMagic.MotionMagicCruiseVelocity = 20; // 8.0;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/utils/FieldUtils.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ public static Pose2d getCurrentHubPose() {

public enum FeedTargets {
BLUE_BACK_RIGHT(new Translation2d(0.6643, 3)), // Eyeballed in Choreo
BLUE_BACK_LEFT(new Translation2d(0.75, 7)),
BLUE_BACK_LEFT(new Translation2d(0.75, 6)),
RED_BACK_RIGHT(ChoreoAllianceFlipUtil.flip(BLUE_BACK_RIGHT.getPose())),
RED_BACK_LEFT(ChoreoAllianceFlipUtil.flip(BLUE_BACK_LEFT.getPose()));

Expand Down
40 changes: 8 additions & 32 deletions src/main/java/frc/robot/utils/autoaim/ShotTrees.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,17 +106,17 @@ public class ShotTrees {
1.13));

// budget shots
COMP_HUB_SHOT_TREE.put(4.172776, new ShotData(Rotation2d.fromDegrees(36), 0.95 * 25.5, 1.13));
COMP_HUB_SHOT_TREE.put(4.172776, new ShotData(Rotation2d.fromDegrees(36), 0.97 * 25.5, 1.13));

COMP_HUB_SHOT_TREE.put(4.512483, new ShotData(Rotation2d.fromDegrees(34), 0.95 * 25.5, 1.2));
COMP_HUB_SHOT_TREE.put(4.512483, new ShotData(Rotation2d.fromDegrees(34), 0.97 * 25.5, 1.2));

COMP_HUB_SHOT_TREE.put(4.974656, new ShotData(Rotation2d.fromDegrees(39), 0.95 * 27, 1.2));
COMP_HUB_SHOT_TREE.put(4.974656, new ShotData(Rotation2d.fromDegrees(39), 0.97 * 27, 1.2));

COMP_HUB_SHOT_TREE.put(5.116029, new ShotData(Rotation2d.fromDegrees(39.5), 0.95 * 27.5, 1.1));
COMP_HUB_SHOT_TREE.put(5.116029, new ShotData(Rotation2d.fromDegrees(39.5), 0.97 * 27.5, 1.1));

COMP_HUB_SHOT_TREE.put(5.509574, new ShotData(Rotation2d.fromDegrees(40), 0.95 * 28, 1.12));
COMP_HUB_SHOT_TREE.put(5.509574, new ShotData(Rotation2d.fromDegrees(40), 0.97 * 28, 1.12));

COMP_HUB_SHOT_TREE.put(5.63499, new ShotData(Rotation2d.fromDegrees(40), 0.95 * 28, 1.12));
COMP_HUB_SHOT_TREE.put(5.63499, new ShotData(Rotation2d.fromDegrees(40), 0.97 * 28, 1.12));

// COMP_HUB_SHOT_TREE.put(
// 4.602258,
Expand Down Expand Up @@ -147,41 +147,17 @@ public class ShotTrees {
public static final InterpolatingShotTree FEED_SHOT_TREE = new InterpolatingShotTree();

static { // For feed shot tree
FEED_SHOT_TREE.put(
Units.feetToMeters(2), new ShotData(Rotation2d.fromDegrees(23.16), 20 - 2, 0)); // - 2, 0));
FEED_SHOT_TREE.put(
Units.feetToMeters(4),
new ShotData(Rotation2d.fromDegrees(30), 40 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(6),
new ShotData(Rotation2d.fromDegrees(40), 30 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(8),
new ShotData(Rotation2d.fromDegrees(40), 32 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(10),
new ShotData(Rotation2d.fromDegrees(40), 35 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(12),
new ShotData(Rotation2d.fromDegrees(40), 40 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(14),
new ShotData(Rotation2d.fromDegrees(45), 38 - 2, 0.0)); // - 2, 0.0));
FEED_SHOT_TREE.put(
Units.feetToMeters(16),
new ShotData(Rotation2d.fromDegrees(45), 40 - 2, 0.0)); // - 2, 0.0));

FEED_SHOT_TREE.put(
Units.feetToMeters(18),
new ShotData(
Rotation2d.fromDegrees(40 - 13.16),
36 * 0.84615384615 / TurretSubsystem.OLD_FLYWHEEL_GEAR_RATIO + 1,
0.9 * (36 * 0.84615384615 / TurretSubsystem.OLD_FLYWHEEL_GEAR_RATIO + 1),
1.42)); // - 2, 1.42));
FEED_SHOT_TREE.put(
Units.feetToMeters(20),
new ShotData(
Rotation2d.fromDegrees(43 - 13.16),
38 * 0.84615384615 / TurretSubsystem.OLD_FLYWHEEL_GEAR_RATIO + 1,
0.9 * (38 * 0.84615384615 / TurretSubsystem.OLD_FLYWHEEL_GEAR_RATIO + 1),
1.36)); // - 2, 1.36));
FEED_SHOT_TREE.put(
Units.feetToMeters(22),
Expand Down
Loading