Skip to content

Commit eb43714

Browse files
committed
Shooter adjustments
1 parent ce72e90 commit eb43714

2 files changed

Lines changed: 27 additions & 15 deletions

File tree

src/main/java/frc/robot/BuildConstants.java

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 346;
9-
public static final String GIT_SHA = "fcf8829b06301b17107b8cc0514afcee04946385";
10-
public static final String GIT_DATE = "2024-08-18 11:34:34 EDT";
11-
public static final String GIT_BRANCH = "marc";
12-
public static final String BUILD_DATE = "2024-08-18 15:14:30 EDT";
13-
public static final long BUILD_UNIX_TIME = 1724008470026L;
8+
public static final int GIT_REVISION = 347;
9+
public static final String GIT_SHA = "ce72e903bd56c27c1efd826909dae699468e1732";
10+
public static final String GIT_DATE = "2024-08-18 23:42:15 EDT";
11+
public static final String GIT_BRANCH = "pre-goonettes";
12+
public static final String BUILD_DATE = "2024-08-29 21:12:59 EDT";
13+
public static final long BUILD_UNIX_TIME = 1724980379162L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}

src/main/java/frc/robot/commands/AimbotTele.java

Lines changed: 21 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -108,21 +108,27 @@ public void angleShooter() {
108108
if (DriverStation.getAlliance().isPresent()) this.alliance = DriverStation.getAlliance().get();
109109
// Logger.recordOutput("distance to speak", Units.metersToFeet(distanceToSpeakerMeter));
110110
distanceToSpeakerMeter = calculateDistanceToSpeaker();
111-
if (Units.metersToFeet(distanceToSpeakerMeter) > 12) {
111+
if (Units.metersToFeet(distanceToSpeakerMeter) < 6) {
112+
shooter.setFlywheelRPMs(4500, 4000);
113+
// } else {
114+
// shooter.setFlywheelRPMs(5700, 5400);
115+
// }
116+
} else if (Units.metersToFeet(distanceToSpeakerMeter) > 11.6) {
112117
// double shootingSpeed =
113118
// MathUtil.clamp(
114119
// calculateShooterSpeed(Units.metersToFeet(distanceToSpeakerMeter)), 3250, 5400);
115120
double shootingSpeed = calculateShooterSpeed(Units.metersToFeet(distanceToSpeakerMeter));
116121

117122
shooter.setFlywheelRPMs(shootingSpeed, shootingSpeed + 100);
118123
} else shooter.setFlywheelRPMs(5700, 5400);
124+
119125
pivot.setPivotGoal(calculatePivotAngleDeg(distanceToSpeakerMeter));
120126
}
121127

122128
private double calculateShooterSpeed(double distanceToSpeakerFeet) {
123129
double shooterSpeed = -986.49 * distanceToSpeakerFeet + 17294.6;
124130
// shooterSpeed = MathUtil.clamp(shooterSpeed, 3850, 5400);
125-
shooterSpeed = MathUtil.clamp(shooterSpeed, 4000, 5400);
131+
shooterSpeed = MathUtil.clamp(shooterSpeed, 4400, 5400);
126132
// if (distanceToSpeakerFeet >= 11) {
127133
// return -430.7 * distanceToSpeakerFeet + 8815;
128134
// } else return -600. * distanceToSpeakerFeet + 10406;
@@ -132,15 +138,21 @@ private double calculateShooterSpeed(double distanceToSpeakerFeet) {
132138
private double calculatePivotAngleDeg(double distanceToSpeakerMeter) {
133139
// pivotSetpointDeg = (-0.272 * Math.abs(Units.metersToInches(distanceToSpeakerMeter) - 36) +
134140
// 60);
135-
pivotSetpointDeg =
136-
(-0.253 * Math.abs(Units.metersToInches(distanceToSpeakerMeter) - 36) + 57.68);
137-
pivotSetpointDeg = MathUtil.clamp(pivotSetpointDeg, 34, 62);
141+
// pivotSetpointDeg =
142+
// (-0.253 * Math.abs(Units.metersToInches(distanceToSpeakerMeter) - 36) + 57.68);
143+
// pivotSetpointDeg = MathUtil.clamp(pivotSetpointDeg, 34, 62);
138144

139-
if (Units.metersToFeet(distanceToSpeakerMeter) > 12) {
140-
return 34;
145+
// if (Units.metersToFeet(distanceToSpeakerMeter) > 12) {
146+
// return 34;
147+
// }
148+
// Logger.recordOutput("pivot target auto", pivotSetpointDeg);
149+
// return pivotSetpointDeg + 3.3;
150+
pivotSetpointDeg = Units.radiansToDegrees(Math.atan(2.1 / distanceToSpeakerMeter));
151+
if (Units.metersToFeet(distanceToSpeakerMeter) > 11.6) {
152+
return 32;
141153
}
142-
Logger.recordOutput("pivot target auto", pivotSetpointDeg);
143-
return pivotSetpointDeg + 3.3;
154+
pivotSetpointDeg = MathUtil.clamp(pivotSetpointDeg, 32, 62);
155+
return pivotSetpointDeg;
144156
}
145157

146158
private double calculateDistanceToSpeaker() {

0 commit comments

Comments
 (0)