Skip to content

Commit 495ea82

Browse files
j
1 parent 6f9a945 commit 495ea82

File tree

2 files changed

+37
-31
lines changed

2 files changed

+37
-31
lines changed

src/main/java/frc/robot/Modules/Mechanisms/VisionSystems.java

+35-28
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
99
import frc.robot.Modules.Calculations;
1010
import frc.robot.Modules.GameControl;
11+
import edu.wpi.first.cameraserver.CameraServer;
1112

1213
public class VisionSystems {
1314
/** Limelight Visions System. Used for Tracking Retro-Reflectors */
@@ -25,9 +26,9 @@ public static enum Limelight_Light_States {
2526
blink
2627
}
2728

28-
/**
29-
* This function is used to update the SmartDashboard with the current values of the Limelight
30-
*/
29+
/**
30+
* This function is used to update the SmartDashboard with the current values of the Limelight
31+
*/
3132
public static void updateSmartDashboard() {
3233
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
3334

@@ -51,22 +52,22 @@ public static void updateSmartDashboard() {
5152

5253
}
5354

54-
/**
55-
* This function returns the distance from the center of the limelight to the center of the hub stack
56-
*
57-
* @return The distance from the center of the limelight to the center of the hub stack.
58-
*/
55+
/**
56+
* This function returns the distance from the center of the limelight to the center of the hub stack
57+
*
58+
* @return The distance from the center of the limelight to the center of the hub stack.
59+
*/
5960
public static double getDistanceFromHubStack() {
6061
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
6162
double verticalAngle = table.getEntry("ty").getDouble(0);
6263
return ((RobotInformation.FieldData.upperHubHeightMeters-RobotInformation.RobotData.RobotMeasurement.LimelightHeightMeters) / (Math.tan((RobotInformation.RobotData.RobotMeasurement.LimelightAngleRadians + Math.toRadians(verticalAngle)))));
6364
}
6465

6566
/**
66-
* Is the top hub present in the FOV?
67-
*
68-
* @return A boolean value.
69-
*/
67+
* Is the top hub present in the FOV?
68+
*
69+
* @return A boolean value.
70+
*/
7071
public static boolean hubPresent() {
7172
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
7273
double targetPresence = table.getEntry("tv").getDouble(0);
@@ -77,37 +78,37 @@ public static boolean hubPresent() {
7778
}
7879
}
7980

80-
/**
81-
* Initialises the Limelight for Top Hub tracking: Sets the LEDS to on, sets the pipeline to 0, and sets the Limelight as a Vision Processor
82-
*/
81+
/**
82+
* Initialises the Limelight for Top Hub tracking: Sets the LEDS to on, sets the pipeline to 0, and sets the Limelight as a Vision Processor
83+
*/
8384
public static void init() {
8485
setLEDS(Limelight_Light_States.blink);
8586
NetworkTableInstance.getDefault().getTable("limelight").getEntry("pipeline").setNumber(0); //Sets the pipeline to 0
8687
NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(0); //Sets the Limelight as a Vision Proccesor
8788
}
8889

89-
/**
90-
* Sets the pipeline to the value of pipeline
91-
*
92-
* @param pipeline 0-10
93-
*/
90+
/**
91+
* Sets the pipeline to the value of pipeline
92+
*
93+
* @param pipeline 0-10
94+
*/
9495
public static void setPipeline(double pipeline) {
9596
NetworkTableInstance.getDefault().getTable("limelight").getEntry("pipeline").setNumber(pipeline); //Sets the pipeline to pipeline
9697
}
9798

98-
/**
99-
* Code run for limelight when robot is in a disabled state
100-
*/
99+
/**
100+
* Code run for limelight when robot is in a disabled state
101+
*/
101102
public static void disabled() {
102103
setLEDS(Limelight_Light_States.off); // Turns off the god damm limelight cause im going to go blind and gouge my eyes out because wtf does it need to be so bright like holy hell
103104
}
104105

105106

106-
/**
107-
* This function sets the LED mode of the limelight
108-
*
109-
* @param mode Limelight_Light_States on, off, blink
110-
*/
107+
/**
108+
* This function sets the LED mode of the limelight
109+
*
110+
* @param mode Limelight_Light_States on, off, blink
111+
*/
111112
public static void setLEDS(Limelight_Light_States mode) {
112113
switch (mode) {
113114
case on:
@@ -154,4 +155,10 @@ public static void coprocessorErrorCheck() {
154155
}
155156
}
156157
}
158+
159+
public static class intakeVision {
160+
public static void init() {
161+
CameraServer.startAutomaticCapture("Ball Camera", 0);
162+
}
163+
}
157164
}

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

+2-3
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222
import frc.robot.Modules.GameControl.MatchTypes;
2323
import frc.robot.Modules.GameControl.UserControl.RobotLEDState;
2424
import frc.robot.Modules.Mechanisms.VisionSystems.Limelight.Limelight_Light_States;
25-
import edu.wpi.first.cameraserver.CameraServer;
2625
import edu.wpi.first.wpilibj.Joystick;
2726
import edu.wpi.first.wpilibj.RobotController;
2827
import edu.wpi.first.wpilibj.SerialPort;
@@ -106,8 +105,8 @@ public void robotInit() {
106105
// Robot Visual Control
107106
RobotLEDStateCounter = 0;
108107
GameControl.UserControl.currentRobotLEDState = RobotLEDState.off;
109-
110-
CameraServer.startAutomaticCapture("Ball Camera", 0);
108+
VisionSystems.intakeVision.init();
109+
111110
GameControl.UserControl.ledCounter = 0;
112111
GameControl.UserControl.oldLedValue = 0;
113112

0 commit comments

Comments
 (0)