Skip to content

Commit 7b070cc

Browse files
committed
...
1 parent 9ce0d11 commit 7b070cc

File tree

13 files changed

+418
-378
lines changed

13 files changed

+418
-378
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,23 @@
1515
* (log replay from a file).
1616
*/
1717
public final class Constants {
18-
public static final Mode simMode = Mode.SIM;
19-
public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode;
18+
public static final RobotType robotType = RobotType.DEV;
19+
20+
public static final Mode getMode() {
21+
return switch (robotType) {
22+
case COMP, DEV -> RobotBase.isReal() ? Mode.REAL : Mode.REPLAY;
23+
case SIM -> Mode.SIM;
24+
};
25+
}
26+
27+
public static final Mode currentMode =
28+
RobotBase.isReal() ? Mode.REAL : RobotBase.isSimulation() ? Mode.SIM : Mode.REPLAY;
29+
30+
public static enum RobotType {
31+
COMP,
32+
DEV,
33+
SIM
34+
}
2035

2136
public static enum Mode {
2237
/** Running on a real robot. */

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

Lines changed: 108 additions & 91 deletions
Original file line numberDiff line numberDiff line change
@@ -8,84 +8,102 @@
88
package frc.robot;
99

1010
import com.revrobotics.spark.SparkLowLevel.MotorType;
11-
import com.revrobotics.spark.SparkMax;
11+
import edu.wpi.first.wpilibj.SPI.Port;
1212
import edu.wpi.first.wpilibj.XboxController;
13+
import frc.robot.Constants.Mode;
1314
import frc.robot.subsystem.ballsasorber.ballsasorber;
14-
import frc.robot.subsystem.ballsasorber.ballsasorberIO;
1515
import frc.robot.subsystem.ballsasorber.ballsasorberIODev;
1616
import frc.robot.subsystem.ballsshooter.ballsshooter;
17-
import frc.robot.subsystem.ballsshooter.ballsshooterIO;
1817
import frc.robot.subsystem.ballsshooter.ballsshooterIODev;
1918
import frc.robot.subsystem.drivebase.drivebase;
2019
import frc.robot.subsystem.drivebase.drivebaseIODev;
21-
import edu.wpi.first.wpilibj.SPI.Port;
2220
import org.littletonrobotics.junction.LogFileUtil;
2321
import org.littletonrobotics.junction.LoggedRobot;
2422
import org.littletonrobotics.junction.Logger;
2523
import org.littletonrobotics.junction.networktables.NT4Publisher;
2624
import org.littletonrobotics.junction.wpilog.WPILOGReader;
2725
import org.littletonrobotics.junction.wpilog.WPILOGWriter;
26+
2827
/**
29-
* The VM is configured to automatically run this class, and to call the
30-
* functions corresponding to each mode, as described in the TimedRobot
31-
* documentation. If you change the name of this class or the package after
32-
* creating this project, you must also update the build.gradle file in the
28+
* The VM is configured to automatically run this class, and to call the functions corresponding to
29+
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
30+
* the package after creating this project, you must also update the build.gradle file in the
3331
* project.
3432
*/
3533
public class Robot extends LoggedRobot {
3634
private XboxController xboxController;
37-
private ballsasorberIODev ballsasorberIODev;
38-
private ballsshooterIODev ballsshooterIODev;
39-
private drivebaseIODev drivebaseIODev;
35+
private ballsasorber ballsasorber;
36+
private ballsshooter ballsshooter;
37+
private drivebase drivebase;
4038
boolean asorbing = false;
4139
boolean moving = false;
4240
boolean throwing = false;
4341
Port gyroport = Port.kOnboardCS0;
44-
42+
4543
public Robot() {
4644
// Record metadata
4745
this.xboxController = new XboxController(0);
48-
this.ballsasorberIODev = new ballsasorberIODev(1, MotorType.kBrushless);
49-
this.ballsshooterIODev = new ballsshooterIODev(2, MotorType.kBrushless, 1, MotorType.kBrushless);
50-
this.drivebaseIODev = new drivebaseIODev(3, MotorType.kBrushless, 4, MotorType.kBrushless, 5, MotorType.kBrushless, 6, MotorType.kBrushless, 12, gyroport);
46+
5147
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
5248
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
5349
Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA);
5450
Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE);
5551
Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH);
56-
Logger.recordMetadata(
57-
"GitDirty",
58-
switch (BuildConstants.DIRTY) {
59-
case 0 -> "All changes committed";
60-
case 1 -> "Uncommitted changes";
61-
default -> "Unknown";
62-
});
63-
64-
// Set up data receivers & replay source
65-
switch (Constants.currentMode) {
66-
case REAL:
67-
// Running on a real robot, log to a USB stick ("/U/logs")
68-
Logger.addDataReceiver(new WPILOGWriter());
69-
Logger.addDataReceiver(new NT4Publisher());
70-
break;
71-
72-
case SIM:
73-
// Running a physics simulator, log to NT
74-
Logger.addDataReceiver(new NT4Publisher());
75-
break;
76-
77-
case REPLAY:
78-
// Replaying a log, set up replay source
79-
setUseTiming(false); // Run as fast as possible
80-
String logPath = LogFileUtil.findReplayLog();
81-
Logger.setReplaySource(new WPILOGReader(logPath));
82-
Logger.addDataReceiver(new WPILOGWriter(
83-
LogFileUtil.addPathSuffix(logPath, "_sim")));
84-
break;
52+
Logger.recordMetadata(
53+
"GitDirty",
54+
switch (BuildConstants.DIRTY) {
55+
case 0 -> "All changes committed";
56+
case 1 -> "Uncommitted changes";
57+
default -> "Unknown";
58+
});
59+
60+
// Set up data receivers & replay source
61+
switch (Constants.currentMode) {
62+
case REAL:
63+
// Running on a real robot, log to a USB stick ("/U/logs")
64+
Logger.addDataReceiver(new WPILOGWriter());
65+
Logger.addDataReceiver(new NT4Publisher());
66+
break;
67+
68+
case SIM:
69+
// Running a physics simulator, log to NT
70+
Logger.addDataReceiver(new NT4Publisher());
71+
break;
72+
73+
case REPLAY:
74+
// Replaying a log, set up replay source
75+
setUseTiming(false); // Run as fast as possible
76+
String logPath = LogFileUtil.findReplayLog();
77+
Logger.setReplaySource(new WPILOGReader(logPath));
78+
Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim")));
79+
break;
80+
}
81+
82+
// Start AdvantageKit logger
83+
Logger.start();
84+
85+
if (Constants.getMode() != Mode.REPLAY) {
86+
switch (Constants.robotType) {
87+
case COMP -> {
88+
drivebase =
89+
new drivebase(new drivebaseIODev(0, null, 0, null, 0, null, 0, null, 0, gyroport));
90+
ballsasorber = new ballsasorber(new ballsasorberIODev(1, MotorType.kBrushless));
91+
ballsshooter = new ballsshooter(new ballsshooterIODev(0, null, 0, null));
92+
}
93+
case DEV -> {
94+
drivebase =
95+
new drivebase(new drivebaseIODev(0, null, 0, null, 0, null, 0, null, 0, gyroport));
96+
ballsasorber = new ballsasorber(new ballsasorberIODev(1, MotorType.kBrushless));
97+
ballsshooter = new ballsshooter(new ballsshooterIODev(0, null, 0, null));
98+
}
99+
case SIM -> {
100+
drivebase =
101+
new drivebase(new drivebaseIODev(0, null, 0, null, 0, null, 0, null, 0, gyroport));
102+
ballsasorber = new ballsasorber(new ballsasorberIODev(1, MotorType.kBrushless));
103+
ballsshooter = new ballsshooter(new ballsshooterIODev(0, null, 0, null));
85104
}
86-
87-
// Start AdvantageKit logger
88-
Logger.start();
105+
}
106+
}
89107
}
90108

91109
/** This function is called periodically during all modes. */
@@ -100,18 +118,15 @@ public void disabledInit() {}
100118
@Override
101119
public void disabledPeriodic() {}
102120

103-
/**
104-
* This autonomous runs the autonomous command selected by your {@link
105-
* RobotContainer} class.
106-
*/
121+
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
107122
@Override
108123
public void autonomousInit() {}
109124

110125
/** This function is called periodically during autonomous. */
111126
@Override
112127
public void autonomousPeriodic() {
113-
//start at right side at blue line
114-
128+
// start at right side at blue line
129+
115130
}
116131

117132
/** This function is called once when teleop is enabled. */
@@ -122,68 +137,70 @@ public void teleopInit() {}
122137
@Override
123138
public void teleopPeriodic() {
124139
if (xboxController.getBButtonPressed() == true && throwing == false) {
125-
ballsasorberIODev.startsucking(1);
126-
asorbing = true;
127-
}else if (xboxController.getBButtonReleased() == true && asorbing == true){
140+
ballsasorber.startsucking(1);
141+
asorbing = true;
142+
} else if (xboxController.getBButtonReleased() == true && asorbing == true) {
128143
asorbing = false;
129-
ballsasorberIODev.stopsucking();
130-
}else if (xboxController.getAButtonPressed() == true && asorbing == false) {
131-
ballsshooterIODev.startshooting(1);
132-
throwing = true;
133-
}else if (xboxController.getAButtonReleased() == true && throwing == true){
144+
ballsasorber.stopsucking();
145+
} else if (xboxController.getAButtonPressed() == true && asorbing == false) {
146+
ballsshooter.startshooting(1);
147+
throwing = true;
148+
} else if (xboxController.getAButtonReleased() == true && throwing == true) {
134149
throwing = false;
135-
ballsshooterIODev.stopshooting();
136-
}else if (xboxController.getLeftX() == 1){
150+
ballsshooter.stopshooting();
151+
} else if (xboxController.getLeftX() == 1) {
137152
if (moving == false) {
138-
drivebaseIODev.turn(1,"right");
153+
drivebase.turn(1, "right");
139154
moving = true;
140-
}else{
141-
drivebaseIODev.stop();
142-
drivebaseIODev.turn(1,"right");
155+
} else {
156+
drivebase.stop();
157+
drivebase.turn(1, "right");
143158
}
144-
}else if (xboxController.getLeftX() == -1){
159+
} else if (xboxController.getLeftX() == -1) {
145160
if (moving == false) {
146-
drivebaseIODev.turn(1,"left");
161+
drivebase.turn(1, "left");
147162
moving = true;
148-
}else{
149-
drivebaseIODev.stop();
150-
drivebaseIODev.turn(1,"left");
163+
} else {
164+
drivebase.stop();
165+
drivebase.turn(1, "left");
151166
}
152-
}else if (xboxController.getLeftY() == -1 ){
167+
} else if (xboxController.getLeftY() == -1) {
153168
if (moving == false) {
154-
drivebaseIODev.forward(1);
169+
drivebase.forward(1);
155170
moving = true;
156-
}else{
157-
drivebaseIODev.stop();
158-
drivebaseIODev.forward(1);
171+
} else {
172+
drivebase.stop();
173+
drivebase.forward(1);
159174
}
160-
}else if (xboxController.getLeftY() == 1 ){
175+
} else if (xboxController.getLeftY() == 1) {
161176
if (moving == false) {
162-
drivebaseIODev.backward(1);
177+
drivebase.backward(1);
163178
moving = true;
164-
}else{
165-
drivebaseIODev.stop();
166-
drivebaseIODev.backward(1);
179+
} else {
180+
drivebase.stop();
181+
drivebase.backward(1);
167182
}
168-
}else if(xboxController.getLeftY() < -0.2 && xboxController.getLeftY() > 0.2 && xboxController.getLeftX() < -0.2 && xboxController.getLeftX() > 0.2){
169-
drivebaseIODev.stop();
183+
} else if (xboxController.getLeftY() < -0.2
184+
&& xboxController.getLeftY() > 0.2
185+
&& xboxController.getLeftX() < -0.2
186+
&& xboxController.getLeftX() > 0.2) {
187+
drivebase.stop();
170188
moving = false;
171189
}
172-
173190
}
174191

175192
/** This function is called once when test mode is enabled. */
176193
@Override
177194
public void testInit() {
178-
try{
179-
drivebaseIODev.turndegress(1, 90, "left");
195+
try {
196+
drivebase.turndegress(1, 90, "left");
180197
Thread.sleep(1000);
181-
drivebaseIODev.turndegress(1, 90, "right");
198+
drivebase.turndegress(1, 90, "right");
182199
Thread.sleep(1000);
183-
drivebaseIODev.forwardincm(1, 5);
200+
drivebase.forwardincm(1, 5);
184201
Thread.sleep(1000);
185-
drivebaseIODev.backwardincm(1,5);
186-
}catch(Exception e){
202+
drivebase.backwardincm(1, 5);
203+
} catch (Exception e) {
187204

188205
}
189206
}
Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,8 @@
11
package frc.robot.subsystem.ballsasorber;
22

3-
import frc.robot.subsystem.ballsasorber.ballsasorberIO.ballsasorberIOinputs;
43
import edu.wpi.first.wpilibj2.command.Command;
54
import edu.wpi.first.wpilibj2.command.SubsystemBase;
6-
5+
import frc.robot.subsystem.ballsasorber.ballsasorberIO.ballsasorberIOinputs;
76

87
public class ballsasorber extends SubsystemBase {
98
private final ballsasorberIO io;
@@ -12,11 +11,12 @@ public class ballsasorber extends SubsystemBase {
1211
public ballsasorber(ballsasorberIO expected_io) {
1312
this.io = expected_io;
1413
}
14+
1515
public Command startsucking(double velocity) {
1616
return run(() -> io.startsucking(velocity));
1717
}
18+
1819
public Command stopsucking() {
1920
return run(() -> io.stopsucking());
2021
}
21-
2222
}

src/main/java/frc/robot/subsystem/ballsasorber/ballsasorberIO.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@ public static class ballsasorberIOinputs {
1313
public default void updateInputs(ballsasorberIOinputs inputs) {}
1414

1515
public default void setVoltage(double voltage) {}
16-
public default void startsucking(double velocity){}
17-
public default void stopsucking(){}
1816

17+
public default void startsucking(double velocity) {}
1918

19+
public default void stopsucking() {}
2020
}
Lines changed: 13 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,25 +1,22 @@
11
package frc.robot.subsystem.ballsasorber;
2+
23
import com.revrobotics.spark.SparkLowLevel.MotorType;
34
import com.revrobotics.spark.SparkMax;
45

5-
6-
76
public class ballsasorberIODev implements ballsasorberIO {
8-
private final SparkMax suckmotor;
9-
7+
private final SparkMax suckmotor;
108

9+
public ballsasorberIODev(int suckmotor, MotorType suckMotorType) {
10+
this.suckmotor = new SparkMax(suckmotor, suckMotorType);
11+
}
1112

12-
public ballsasorberIODev(int suckmotor, MotorType suckMotorType) {
13-
this.suckmotor = new SparkMax(suckmotor, suckMotorType);
14-
}
13+
@Override
14+
public void startsucking(double velocity) {
15+
suckmotor.set(-velocity);
16+
}
1517

16-
@Override
17-
public void startsucking(double velocity){
18-
suckmotor.set(-velocity);
19-
}
20-
@Override
21-
public void stopsucking(){
22-
suckmotor.stopMotor();
23-
}
24-
18+
@Override
19+
public void stopsucking() {
20+
suckmotor.stopMotor();
21+
}
2522
}

0 commit comments

Comments
 (0)