77
88package org .carlmontrobotics .lib199 ;
99
10- import org .carlmontrobotics .MotorConfig ;
11- import org .carlmontrobotics .lib199 .sim .MockSparkMax ;
12- import org .carlmontrobotics .lib199 .sim .MockTalonSRX ;
13- import org .carlmontrobotics .lib199 .sim .MockVictorSPX ;
14-
1510import com .ctre .phoenix .motorcontrol .NeutralMode ;
1611import com .ctre .phoenix .motorcontrol .can .WPI_TalonSRX ;
1712import com .ctre .phoenix .motorcontrol .can .WPI_VictorSPX ;
13+ import com .ctre .phoenix .sensors .CANCoder ;
1814import com .revrobotics .CANSparkMax ;
1915import com .revrobotics .CANSparkMax .ExternalFollower ;
2016import com .revrobotics .CANSparkMax .IdleMode ;
2117import com .revrobotics .CANSparkMaxLowLevel ;
2218import com .revrobotics .SparkMaxPIDController ;
2319
20+ import org .carlmontrobotics .MotorConfig ;
21+ import org .carlmontrobotics .lib199 .sim .MockSparkMax ;
22+ import org .carlmontrobotics .lib199 .sim .MockTalonSRX ;
23+ import org .carlmontrobotics .lib199 .sim .MockVictorSPX ;
24+ import org .carlmontrobotics .lib199 .sim .MockedCANCoder ;
25+
26+ import edu .wpi .first .cameraserver .CameraServer ;
27+ import edu .wpi .first .cscore .UsbCamera ;
28+ import edu .wpi .first .cscore .VideoSource .ConnectionStrategy ;
2429import edu .wpi .first .wpilibj .RobotBase ;
2530
2631/**
27- * A class containing methods to create and configure motor controllers .
32+ * Add your docs here .
2833 */
2934public class MotorControllerFactory {
3035 public static WPI_VictorSPX createVictor (int port ) {
@@ -145,4 +150,47 @@ public static CANSparkMax createSparkMax(int id, MotorConfig config) {
145150 return spark ;
146151 }
147152
148- }
153+ /**
154+ * @deprecated Use {@link SensorFactory#createCANCoder(int)} instead.
155+ */
156+ @ Deprecated
157+ public static CANCoder createCANCoder (int port ) {
158+ CANCoder canCoder = new CANCoder (port );
159+ if (RobotBase .isSimulation ()) new MockedCANCoder (canCoder );
160+ return canCoder ;
161+ }
162+
163+ /**
164+ * Configures a USB Camera.
165+ * See {@link CameraServer#startAutomaticCapture} for more details.
166+ * This MUST be called AFTER AHRS initialization or the code will be unable to connect to the gyro.
167+ *
168+ * @return The configured camera
169+ *
170+ * @deprecated Use {@link SensorFactory#configureCamera()} instead.
171+ */
172+ @ Deprecated
173+ public static UsbCamera configureCamera () {
174+ UsbCamera camera = CameraServer .startAutomaticCapture ();
175+ camera .setConnectionStrategy (ConnectionStrategy .kKeepOpen );
176+ CameraServer .getServer ().setSource (camera );
177+ return camera ;
178+ }
179+
180+ /**
181+ * This method is equivalent to calling {@link #configureCamera()} {@code numCameras} times.
182+ * The last camera will be set as the primary Camera feed.
183+ * To change it, call {@code CameraServer.getServer().setSource()}.
184+ *
185+ * @param numCameras The number of cameras to configure
186+ * @return The configured cameras.
187+ *
188+ * @deprecated Use {@link SensorFactory#configureCameras(int)} instead.
189+ */
190+ @ Deprecated
191+ public static UsbCamera [] configureCameras (int numCameras ) {
192+ UsbCamera [] cameras = new UsbCamera [numCameras ];
193+ for (int i = 0 ; i < numCameras ; i ++) cameras [i ] = configureCamera ();
194+ return cameras ;
195+ }
196+ }
0 commit comments