Skip to content

Commit bc6494e

Browse files
committed
create SensorFactory
1 parent 132ad8a commit bc6494e

2 files changed

Lines changed: 60 additions & 44 deletions

File tree

src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java

Lines changed: 6 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -7,29 +7,24 @@
77

88
package 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+
1015
import com.ctre.phoenix.motorcontrol.NeutralMode;
1116
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
1217
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
13-
import com.ctre.phoenix.sensors.CANCoder;
1418
import com.revrobotics.CANSparkMax;
1519
import com.revrobotics.CANSparkMax.ExternalFollower;
1620
import com.revrobotics.CANSparkMax.IdleMode;
1721
import com.revrobotics.CANSparkMaxLowLevel;
1822
import com.revrobotics.SparkMaxPIDController;
1923

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;
2924
import edu.wpi.first.wpilibj.RobotBase;
3025

3126
/**
32-
* Add your docs here.
27+
* A class containing methods to create and configure motor controllers.
3328
*/
3429
public class MotorControllerFactory {
3530
public static WPI_VictorSPX createVictor(int port) {
@@ -150,37 +145,4 @@ public static CANSparkMax createSparkMax(int id, MotorConfig config) {
150145
return spark;
151146
}
152147

153-
public static CANCoder createCANCoder(int port) {
154-
CANCoder canCoder = new CANCoder(port);
155-
if(RobotBase.isSimulation()) new MockedCANCoder(canCoder);
156-
return canCoder;
157-
}
158-
159-
/**
160-
* Configures a USB Camera.
161-
* See {@link CameraServer#startAutomaticCapture} for more details.
162-
* This MUST be called AFTER AHRS initialization or the code will be unable to connect to the gyro.
163-
*
164-
* @return The configured camera
165-
*/
166-
public static UsbCamera configureCamera() {
167-
UsbCamera camera = CameraServer.startAutomaticCapture();
168-
camera.setConnectionStrategy(ConnectionStrategy.kKeepOpen);
169-
CameraServer.getServer().setSource(camera);
170-
return camera;
171-
}
172-
173-
/**
174-
* This method is equivalent to calling {@link #configureCamera()} {@code numCameras} times.
175-
* The last camera will be set as the primary Camera feed.
176-
* To change it, call {@code CameraServer.getServer().setSource()}.
177-
*
178-
* @param numCameras The number of cameras to configure
179-
* @return The configured cameras.
180-
*/
181-
public static UsbCamera[] configureCameras(int numCameras) {
182-
UsbCamera[] cameras = new UsbCamera[numCameras];
183-
for(int i = 0; i < numCameras; i++) cameras[i] = configureCamera();
184-
return cameras;
185-
}
186148
}
Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,54 @@
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+
public static CANCoder createCANCoder(int port) {
17+
CANCoder canCoder = new CANCoder(port);
18+
if (RobotBase.isSimulation())
19+
new MockedCANCoder(canCoder);
20+
return canCoder;
21+
}
22+
23+
/**
24+
* Configures a USB Camera.
25+
* See {@link CameraServer#startAutomaticCapture} for more details.
26+
* This MUST be called AFTER AHRS initialization or the code will be unable to
27+
* connect to the gyro.
28+
*
29+
* @return The configured camera
30+
*/
31+
public static UsbCamera configureCamera() {
32+
UsbCamera camera = CameraServer.startAutomaticCapture();
33+
camera.setConnectionStrategy(ConnectionStrategy.kKeepOpen);
34+
CameraServer.getServer().setSource(camera);
35+
return camera;
36+
}
37+
38+
/**
39+
* This method is equivalent to calling {@link #configureCamera()}
40+
* {@code numCameras} times.
41+
* The last camera will be set as the primary Camera feed.
42+
* To change it, call {@code CameraServer.getServer().setSource()}.
43+
*
44+
* @param numCameras The number of cameras to configure
45+
* @return The configured cameras.
46+
*/
47+
public static UsbCamera[] configureCameras(int numCameras) {
48+
UsbCamera[] cameras = new UsbCamera[numCameras];
49+
for (int i = 0; i < numCameras; i++)
50+
cameras[i] = configureCamera();
51+
return cameras;
52+
}
53+
54+
}

0 commit comments

Comments
 (0)