Skip to content
This repository was archived by the owner on Feb 15, 2025. It is now read-only.

Commit 3b6b863

Browse files
authored
Merge pull request #110 from midtownrobotics/dev
Dev
2 parents 2417878 + fbeffe3 commit 3b6b863

20 files changed

+237
-208
lines changed

.SysId/sysid.json

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
{}

.gitignore

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
# This gitignore has been specially created by the WPILib team.
22
# If you remove items from this file, intellisense might break.
33

4+
# Panjabi MC IS the G.O.A.T.
5+
6+
BuildConstants.java
7+
48
### C++ ###
59
# Prerequisites
610
*.d

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

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,12 @@ public final class BuildConstants {
77
public static final String MAVEN_GROUP = "";
88
public static final String MAVEN_NAME = "2024-Offseason";
99
public static final String VERSION = "unspecified";
10-
public static final int GIT_REVISION = 200;
11-
public static final String GIT_SHA = "0fd5eba2e63c561a4c2921b9c8ff214a9dd32ac6";
12-
public static final String GIT_DATE = "2024-10-19 16:45:45 GMT";
13-
public static final String GIT_BRANCH = "GRITS-Ankit-5am";
14-
public static final String BUILD_DATE = "2024-10-19 18:52:32 GMT";
15-
public static final long BUILD_UNIX_TIME = 1729363952616L;
10+
public static final int GIT_REVISION = 204;
11+
public static final String GIT_SHA = "d7243b7c1c97d3381ea8662f67d91dc0669ab0bb";
12+
public static final String GIT_DATE = "2024-10-26 01:54:30 GMT";
13+
public static final String GIT_BRANCH = "63-update-revctre-classes";
14+
public static final String BUILD_DATE = "2024-10-28 23:30:20 GMT";
15+
public static final long BUILD_UNIX_TIME = 1730158220273L;
1616
public static final int DIRTY = 1;
1717

1818
private BuildConstants(){}

src/main/java/frc/robot/Constants.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ public final class Constants {
1313
public static final double JOYSTICK_THRESHOLD = 0.1;
1414
public static final double CONTROL_LIMITER = 1;
1515
public static final double THEORETICAL_RESTING_VOLTAGE = 12;
16+
public static final double RUMBLE_DURATION = 1;
1617

1718
public static enum Mode {
1819
REAL,

src/main/java/frc/robot/LimelightHelpers.java

Lines changed: 28 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@
2020
import edu.wpi.first.networktables.NetworkTableEntry;
2121
import edu.wpi.first.networktables.NetworkTableInstance;
2222
import edu.wpi.first.networktables.TimestampedDoubleArray;
23-
import frc.robot.LimelightHelpers.LimelightResults;
24-
import frc.robot.LimelightHelpers.PoseEstimate;
23+
// import frc.robot.LimelightHelpers.LimelightResults;
24+
// import frc.robot.LimelightHelpers.PoseEstimate;
2525
import java.io.IOException;
2626
import java.net.HttpURLConnection;
2727
import java.net.MalformedURLException;
@@ -604,32 +604,32 @@ private static PoseEstimate getBotPoseEstimate(String limelightName, String entr
604604
pose, adjustedTimestamp, latency, tagCount, tagSpan, tagDist, tagArea, rawFiducials);
605605
}
606606

607-
private static RawFiducial[] getRawFiducials(String limelightName) {
608-
var entry = LimelightHelpers.getLimelightNTTableEntry(limelightName, "rawfiducials");
609-
var rawFiducialArray = entry.getDoubleArray(new double[0]);
610-
int valsPerEntry = 7;
611-
if (rawFiducialArray.length % valsPerEntry != 0) {
612-
return new RawFiducial[0];
613-
}
614-
615-
int numFiducials = rawFiducialArray.length / valsPerEntry;
616-
RawFiducial[] rawFiducials = new RawFiducial[numFiducials];
617-
618-
for (int i = 0; i < numFiducials; i++) {
619-
int baseIndex = i * valsPerEntry;
620-
int id = (int) extractArrayEntry(rawFiducialArray, baseIndex);
621-
double txnc = extractArrayEntry(rawFiducialArray, baseIndex + 1);
622-
double tync = extractArrayEntry(rawFiducialArray, baseIndex + 2);
623-
double ta = extractArrayEntry(rawFiducialArray, baseIndex + 3);
624-
double distToCamera = extractArrayEntry(rawFiducialArray, baseIndex + 4);
625-
double distToRobot = extractArrayEntry(rawFiducialArray, baseIndex + 5);
626-
double ambiguity = extractArrayEntry(rawFiducialArray, baseIndex + 6);
627-
628-
rawFiducials[i] = new RawFiducial(id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
629-
}
630-
631-
return rawFiducials;
632-
}
607+
// private static RawFiducial[] getRawFiducials(String limelightName) {
608+
// var entry = LimelightHelpers.getLimelightNTTableEntry(limelightName, "rawfiducials");
609+
// var rawFiducialArray = entry.getDoubleArray(new double[0]);
610+
// int valsPerEntry = 7;
611+
// if (rawFiducialArray.length % valsPerEntry != 0) {
612+
// return new RawFiducial[0];
613+
// }
614+
615+
// int numFiducials = rawFiducialArray.length / valsPerEntry;
616+
// RawFiducial[] rawFiducials = new RawFiducial[numFiducials];
617+
618+
// for (int i = 0; i < numFiducials; i++) {
619+
// int baseIndex = i * valsPerEntry;
620+
// int id = (int) extractArrayEntry(rawFiducialArray, baseIndex);
621+
// double txnc = extractArrayEntry(rawFiducialArray, baseIndex + 1);
622+
// double tync = extractArrayEntry(rawFiducialArray, baseIndex + 2);
623+
// double ta = extractArrayEntry(rawFiducialArray, baseIndex + 3);
624+
// double distToCamera = extractArrayEntry(rawFiducialArray, baseIndex + 4);
625+
// double distToRobot = extractArrayEntry(rawFiducialArray, baseIndex + 5);
626+
// double ambiguity = extractArrayEntry(rawFiducialArray, baseIndex + 6);
627+
628+
// rawFiducials[i] = new RawFiducial(id, txnc, tync, ta, distToCamera, distToRobot, ambiguity);
629+
// }
630+
631+
// return rawFiducials;
632+
// }
633633

634634
public static RawDetection[] getRawDetections(String limelightName) {
635635
var entry = LimelightHelpers.getLimelightNTTableEntry(limelightName, "rawdetections");

src/main/java/frc/robot/Robot.java

Lines changed: 0 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414
import com.pathplanner.lib.commands.PathfindingCommand;
1515

1616
import edu.wpi.first.wpilibj.DriverStation;
17-
import edu.wpi.first.wpilibj.RobotState;
1817
import edu.wpi.first.wpilibj.DriverStation.Alliance;
1918
import edu.wpi.first.wpilibj2.command.Command;
2019
import edu.wpi.first.wpilibj2.command.CommandScheduler;
@@ -88,17 +87,6 @@ public void autonomousInit() {
8887
if (autonCommand != null) {
8988
autonCommand.schedule();
9089
}
91-
String currentAuton = m_robotContainer.getAutonFactory().getAutonCommandString();
92-
double desiredHeading = 0;
93-
if (currentAuton.toLowerCase().contains("amp")) {
94-
desiredHeading = 60;
95-
} else if (currentAuton.toLowerCase().contains("source")) {
96-
desiredHeading = -60;
97-
}
98-
if (Alliance.Red.equals(DriverStation.getAlliance().get())) {
99-
desiredHeading *= -1;
100-
}
101-
m_robotContainer.getDrivetrain().resetHeading(desiredHeading);
10290
}
10391

10492
@Override

src/main/java/frc/robot/RobotContainer.java

Lines changed: 46 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,6 @@
99
import edu.wpi.first.math.geometry.Rotation2d;
1010
import edu.wpi.first.math.kinematics.ChassisSpeeds;
1111
import edu.wpi.first.networktables.NetworkTableInstance;
12-
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
13-
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1412
import edu.wpi.first.wpilibj2.command.Command;
1513
import edu.wpi.first.wpilibj2.command.InstantCommand;
1614
import edu.wpi.first.wpilibj2.command.RunCommand;
@@ -118,6 +116,7 @@ private void configureBindings() {
118116
if (drivingMode != null && drivingMode.get() != null && drivingMode.get().equals("robot")) {
119117
pigeonValue = 0;
120118
}
119+
121120
drivetrain.setDriverDesired(
122121
ChassisSpeeds.fromFieldRelativeSpeeds(
123122
driverX, driverY, driverRot, Rotation2d.fromDegrees(pigeonValue)));
@@ -143,8 +142,13 @@ private void configureBindings() {
143142
},
144143
climber));
145144

146-
driver.a().onTrue(new InstantCommand(() -> drivetrain.resetHeading()));
147-
// Note: These probably do not need to require drivetrain
145+
driver
146+
.a()
147+
.onTrue(
148+
new InstantCommand(
149+
() -> drivetrain.resetHeading()
150+
));
151+
148152
driver
149153
.x()
150154
.whileTrue(
@@ -169,7 +173,10 @@ private void configureBindings() {
169173
driver
170174
.leftTrigger()
171175
.whileTrue(
172-
new StartEndCommand(() -> drivetrain.setBoost(true), () -> drivetrain.setBoost(false)));
176+
new StartEndCommand(
177+
() -> drivetrain.setBoost(true),
178+
() -> drivetrain.setBoost(false)
179+
));
173180

174181
driver
175182
.b()
@@ -241,19 +248,26 @@ private void configureBindings() {
241248
// intake,
242249
// shooter));
243250
operator
244-
.leftTrigger()
245-
.whileTrue(
246-
new StartEndCommand(
247-
() -> {
248-
intake.setState(IntakeState.VOMITING);
249-
shooter.setState(ShooterState.VOMITING);
250-
},
251-
() -> {
252-
shooter.setState(ShooterState.IDLE);
253-
intake.setState(IntakeState.IDLE);
254-
},
255-
intake,
256-
shooter));
251+
.leftBumper()
252+
.whileTrue(
253+
new StartEndCommand(
254+
() -> {intake.setState(IntakeState.VOMITING);
255+
shooter.setState(ShooterState.VOMITING);},
256+
() -> {intake.setState(IntakeState.IDLE);
257+
shooter.setState(ShooterState.IDLE);},
258+
intake,
259+
shooter));
260+
261+
operator
262+
.leftTrigger()
263+
.whileTrue(
264+
new StartEndCommand(
265+
() -> {intake.setState(IntakeState.VOMITING);
266+
shooter.setState(ShooterState.VOMITING);},
267+
() -> {intake.setState(IntakeState.IDLE);
268+
shooter.setState(ShooterState.IDLE);},
269+
intake,
270+
shooter));
257271

258272
operator
259273
.rightTrigger()
@@ -354,6 +368,17 @@ public void initializeSubsystems() {
354368

355369
shooter = new Shooter(flywheelIO, pivotIO, feederIO, limelight);
356370

371+
// Beam break
372+
BeamBreakIO beamBreakIO;
373+
374+
if (Constants.getMode() == Constants.Mode.REAL) {
375+
beamBreakIO = new BeamBreakIODIO(IntakePorts.beamBreak);
376+
} else {
377+
beamBreakIO = new BeamBreakIOSim();
378+
}
379+
380+
beamBreak = new BeamBreak(beamBreakIO);
381+
357382
// Intake
358383

359384
RollerIO rollerIO;
@@ -364,35 +389,20 @@ public void initializeSubsystems() {
364389
rollerIO = new RollerIOSim();
365390
}
366391

367-
intake = new Intake(rollerIO);
392+
intake = new Intake(rollerIO, beamBreak);
368393

369394
// Climber
370395

371396
ClimberIO climberIO;
372397

373398
if (Constants.getMode() == Constants.Mode.REAL) {
374-
climberIO =
375-
new ClimberIONeo(Ports.ClimberPorts.leftClimberID, Ports.ClimberPorts.rightClimberID);
399+
climberIO = new ClimberIONeo(Ports.ClimberPorts.leftClimberID, Ports.ClimberPorts.rightClimberID);
376400
} else {
377401
climberIO = new ClimberIOSim();
378402
}
379403

380404
climber = new Climber(operator, climberIO);
381405

382-
// BeamBreak
383-
384-
BeamBreakIO beamBreakIO;
385-
386-
if (Constants.getMode() == Constants.Mode.REAL) {
387-
beamBreakIO = new BeamBreakIODIO(IntakePorts.beamBreak);
388-
} else {
389-
beamBreakIO = new BeamBreakIOSim();
390-
}
391-
392-
beamBreak =
393-
new BeamBreak(
394-
beamBreakIO, robotState, Ports.driverControllerPort, Ports.operatorControllerPort);
395-
396406
// Drivetrain
397407

398408
// if (Constants.USE_KRAKEN_DRIVETRAIN.get()) { // default value is false which means neo is
@@ -408,13 +418,11 @@ public void initializeSubsystems() {
408418
}
409419

410420
// Robot State
411-
robotState = new RobotState(shooter, climber, intake, drivetrain);
412-
beamBreak.setRobotState(robotState);
421+
robotState = new RobotState(shooter, climber, intake, drivetrain, beamBreak, Ports.driverControllerPort, Ports.operatorControllerPort);
413422

414423
drivingMode = new LoggedDashboardChooser<String>("Driving Mode");
415424
drivingMode.addDefaultOption("Field Relative", "field");
416425
drivingMode.addOption("Robot Relative", "robot");
417-
418426
}
419427

420428
public RobotContainer() {

src/main/java/frc/robot/RobotState.java

Lines changed: 33 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
package frc.robot;
22

3+
import frc.robot.subsystems.BeamBreak.BeamBreak;
34
import org.littletonrobotics.junction.Logger;
4-
55
import frc.robot.Constants.ShooterConstants;
66
import frc.robot.subsystems.Climber.Climber;
77
import frc.robot.subsystems.Drivetrain.Drivetrain;
@@ -10,8 +10,13 @@
1010
import frc.robot.subsystems.Intake.Intake.IntakeState;
1111
import frc.robot.subsystems.Shooter.Shooter;
1212
import frc.robot.subsystems.Shooter.Shooter.ShooterState;
13+
import frc.robot.utils.IOProtectionXboxController;
14+
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
1315

1416
public class RobotState {
17+
public BeamBreak beamBreak;
18+
public IOProtectionXboxController driver;
19+
public IOProtectionXboxController operator;
1520
public Shooter shooter;
1621
public Intake intake;
1722
public Drivetrain drive;
@@ -39,7 +44,14 @@ public enum State {
3944
// private final LoggedDashboardChooser<State> stateChooser = new LoggedDashboardChooser<>("Robot
4045
// State");
4146

42-
public RobotState(Shooter shooter, Climber climber, Intake intake, Drivetrain drive) {
47+
public RobotState(Shooter shooter,
48+
Climber climber,
49+
Intake intake,
50+
Drivetrain drive,
51+
BeamBreak beamBreak,
52+
int driverPort,
53+
int operatorPort) {
54+
4355
// stateChooser.addOption("AMP", State.AMP);
4456
// stateChooser.addOption("AMP_REVVING", State.AMP_REVVING);
4557
// stateChooser.addOption("SUBWOOFER", State.SUBWOOFER);
@@ -53,6 +65,9 @@ public RobotState(Shooter shooter, Climber climber, Intake intake, Drivetrain dr
5365
this.shooter = shooter;
5466
this.intake = intake;
5567
this.drive = drive;
68+
this.beamBreak = beamBreak;
69+
this.driver = new IOProtectionXboxController(driverPort);
70+
this.operator = new IOProtectionXboxController(operatorPort);
5671
}
5772

5873
public State currentState = State.IDLE;
@@ -137,7 +152,7 @@ public void updateState() {
137152
break;
138153
case INTAKING:
139154
shooter.setState(ShooterState.INTAKING);
140-
intake.setState(IntakeState.INTAKING);
155+
intake.setState(IntakeState.INTAKING);
141156
break;
142157
case NOTE_HELD:
143158
shooter.setState(ShooterState.IDLE);
@@ -156,6 +171,8 @@ public void updateState() {
156171
default:
157172
break;
158173
}
174+
175+
setControllerRumble();
159176
}
160177

161178
public ShooterState getShooterState() {
@@ -177,4 +194,16 @@ public void onTeleopInit() {
177194
shooter.setState(ShooterState.IDLE);
178195
intake.setState(IntakeState.IDLE);
179196
}
180-
}
197+
198+
public void setControllerRumble(){
199+
if (beamBreak.isBroken() &&
200+
edu.wpi.first.wpilibj.RobotState.isTeleop() &&
201+
Constants.RUMBLE_DURATION > beamBreak.getBrokenTime()) {
202+
driver.setRumble(RumbleType.kBothRumble, 1);
203+
operator.setRumble(RumbleType.kBothRumble, 1);
204+
} else {
205+
driver.setRumble(RumbleType.kBothRumble, 0);
206+
operator.setRumble(RumbleType.kBothRumble, 0);
207+
}
208+
}
209+
}

src/main/java/frc/robot/commands/auton/AlignWithSpeaker.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
package frc.robot.commands.auton;
22

33
import edu.wpi.first.wpilibj2.command.Command;
4-
import frc.robot.RobotState;
54
import frc.robot.Constants.AutonConstants;
65
import frc.robot.subsystems.Drivetrain.Drivetrain;
76
import frc.robot.subsystems.Drivetrain.Drivetrain.DriveState;

0 commit comments

Comments
 (0)