Skip to content

Commit 5b5c1d3

Browse files
Constants
1 parent e480bd9 commit 5b5c1d3

2 files changed

Lines changed: 8 additions & 12 deletions

File tree

src/main/java/frc/robot/subsystems/vision/MotionTrackerVision.java

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -33,21 +33,13 @@ public class MotionTrackerVision extends SubsystemBase {
3333
0.0001,
3434
0.0001
3535
);
36-
37-
private boolean useQuestNav = false;
38-
private static final boolean calibration = false;
39-
private static final boolean useQueuedFrames = true;
4036

4137
private static final Transform2d robotToQuest = new Transform2d(
42-
!calibration ? Centimeters.of(24.275) : Meters.zero(),
43-
!calibration ? Centimeters.of(26.2) : Meters.zero(),
38+
!VisionConstants.useQuestOffset ? Centimeters.of(24.275) : Meters.zero(),
39+
!VisionConstants.useQuestOffset ? Centimeters.of(26.2) : Meters.zero(),
4440
new Rotation2d(Degrees.of(45))
4541
);
4642

47-
// x: -0.216 y: -0.261
48-
49-
// time: 565-593
50-
// time: 794-831
5143
private final TrackerIO io_;
5244
private final TrackerInputsAutoLogged inputs_;
5345

@@ -108,10 +100,10 @@ public void periodic() {
108100
!inputs_.isTracking ||
109101
RobotState.isDisabled() ||
110102
!zeroed ||
111-
!useQuestNav
103+
!VisionConstants.useQuest
112104
) return;
113105

114-
if (useQueuedFrames) {
106+
if (VisionConstants.useQuestFrameQueue) {
115107
for (PoseFrame frame : inputs_.unreadFrames) {
116108
Pose2d robotPose = frame.questPose().transformBy(robotToQuest.inverse());
117109
double timestamp = frame.dataTimestamp();

src/main/java/frc/robot/subsystems/vision/VisionConstants.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,12 @@
1010

1111
public class VisionConstants {
1212

13+
// QuestNav config
1314
public static final boolean useQuest = true;
1415

16+
public static final boolean useQuestFrameQueue = true; // The queuing and bulk consuming of quest frames
17+
public static final boolean useQuestOffset = true; // Applying the offset to the quest, turn off if measuring offset.
18+
1519
// Limelight Names
1620
public static final String frontLimelightName = "limelight-front";
1721
public static final String backLimelightName = "limelight-back";

0 commit comments

Comments
 (0)