|
| 1 | +package org.carlmontrobotics.lib199; |
| 2 | + |
| 3 | +import org.carlmontrobotics.lib199.sim.MockedCANCoder; |
| 4 | + |
| 5 | +import com.ctre.phoenix.sensors.CANCoder; |
| 6 | + |
| 7 | +import edu.wpi.first.cameraserver.CameraServer; |
| 8 | +import edu.wpi.first.cscore.UsbCamera; |
| 9 | +import edu.wpi.first.cscore.VideoSource.ConnectionStrategy; |
| 10 | +import edu.wpi.first.wpilibj.RobotBase; |
| 11 | + |
| 12 | +/** |
| 13 | + * A class containing methods to create and configure sensors. |
| 14 | + */ |
| 15 | +public class SensorFactory { |
| 16 | + |
| 17 | + /** |
| 18 | + * Creates a CANCoder object, linking it to the simulator if necessary |
| 19 | + * |
| 20 | + * @param port The CAN ID of the CANCoder |
| 21 | + * @return The CANCoder object |
| 22 | + */ |
| 23 | + public static CANCoder createCANCoder(int port) { |
| 24 | + CANCoder canCoder = new CANCoder(port); |
| 25 | + if (RobotBase.isSimulation()) |
| 26 | + new MockedCANCoder(canCoder); |
| 27 | + return canCoder; |
| 28 | + } |
| 29 | + |
| 30 | + /** |
| 31 | + * Configures a USB Camera. |
| 32 | + * See {@link CameraServer#startAutomaticCapture} for more details. |
| 33 | + * This MUST be called AFTER AHRS initialization or the code will be unable to |
| 34 | + * connect to the gyro. |
| 35 | + * |
| 36 | + * @return The configured camera |
| 37 | + */ |
| 38 | + public static UsbCamera configureCamera() { |
| 39 | + UsbCamera camera = CameraServer.startAutomaticCapture(); |
| 40 | + camera.setConnectionStrategy(ConnectionStrategy.kKeepOpen); |
| 41 | + CameraServer.getServer().setSource(camera); |
| 42 | + return camera; |
| 43 | + } |
| 44 | + |
| 45 | + /** |
| 46 | + * This method is equivalent to calling {@link #configureCamera()} |
| 47 | + * {@code numCameras} times. |
| 48 | + * The last camera will be set as the primary Camera feed. |
| 49 | + * To change it, call {@code CameraServer.getServer().setSource()}. |
| 50 | + * |
| 51 | + * @param numCameras The number of cameras to configure |
| 52 | + * @return The configured cameras. |
| 53 | + */ |
| 54 | + public static UsbCamera[] configureCameras(int numCameras) { |
| 55 | + UsbCamera[] cameras = new UsbCamera[numCameras]; |
| 56 | + for (int i = 0; i < numCameras; i++) |
| 57 | + cameras[i] = configureCamera(); |
| 58 | + return cameras; |
| 59 | + } |
| 60 | + |
| 61 | +} |
0 commit comments