Skip to content

Commit 9d608c6

Browse files
Naive AdvantageKit hardware Implementation
1 parent 3c2984c commit 9d608c6

15 files changed

+549
-326
lines changed

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

+8
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,14 @@
2323

2424
public final class Constants {
2525

26+
public enum Mode {
27+
REAL,
28+
SIM,
29+
REPLAY,
30+
}
31+
32+
public static final Mode mode = Mode.REAL;
33+
2634
public static final double loopTime = 0.02;
2735

2836
public static final class CANDevices {

src/main/java/frc/robot/RobotContainer.java

+25-7
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,8 @@
55

66
package frc.robot;
77

8-
import edu.wpi.first.math.geometry.Pose2d;
9-
import edu.wpi.first.math.geometry.Rotation2d;
108
import edu.wpi.first.wpilibj.DigitalInput;
119
import edu.wpi.first.wpilibj.DriverStation;
12-
import edu.wpi.first.wpilibj.Timer;
1310
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
1411
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1512
import edu.wpi.first.wpilibj2.command.Command;
@@ -19,8 +16,13 @@
1916
import frc.robot.Constants.GamePieceMode;
2017
import frc.robot.Constants.Position;
2118
import frc.robot.subsystems.arm.ArmSubsystem;
22-
import frc.robot.subsystems.arm.ArmSubsystem.ActiveArmSide;
2319
import frc.robot.subsystems.arm.ArmSubsystem.ArmPosition;
20+
import frc.robot.subsystems.arm.pivot.PivotIO;
21+
import frc.robot.subsystems.arm.pivot.PivotIOFalcon;
22+
import frc.robot.subsystems.arm.telescope.TelescopeIO;
23+
import frc.robot.subsystems.arm.telescope.TelescopeIOFalcon;
24+
import frc.robot.subsystems.arm.wrist.WristIO;
25+
import frc.robot.subsystems.arm.wrist.WristIOFalcon;
2426
import frc.robot.subsystems.IntakeSubsystem;
2527
import frc.robot.subsystems.LEDManager;
2628
// import frc.robot.subsystems.drive.Drive;
@@ -32,11 +34,11 @@
3234
public class RobotContainer {
3335

3436
// private final Drive drive = new Drive();
35-
private final ArmSubsystem arm = new ArmSubsystem();
36-
private final IntakeSubsystem intake = new IntakeSubsystem(() -> arm.getArmSide());
37+
private final ArmSubsystem arm;
38+
private final IntakeSubsystem intake;
3739
@SuppressWarnings("unused")
3840
private final Vision vision = new Vision();
39-
private final LEDManager ledManager = new LEDManager(() -> arm.getArmSide());
41+
private final LEDManager ledManager;
4042

4143
private final Thrustmaster leftStick = new Thrustmaster(0);
4244
private final Thrustmaster rightStick = new Thrustmaster(1);
@@ -51,6 +53,22 @@ public class RobotContainer {
5153

5254
/** The container for the robot. Contains subsystems, OI devices, and commands. */
5355
public RobotContainer() {
56+
switch (Constants.mode) {
57+
case REAL:
58+
arm = new ArmSubsystem(
59+
new PivotIOFalcon(),
60+
new TelescopeIOFalcon(),
61+
new WristIOFalcon());
62+
break;
63+
default:
64+
arm = new ArmSubsystem(
65+
new PivotIO() {},
66+
new TelescopeIO() {},
67+
new WristIO() {});
68+
}
69+
70+
intake = new IntakeSubsystem(arm::getArmSide);
71+
ledManager = new LEDManager(arm::getArmSide);
5472

5573
configureSubsystems();
5674
configureCompBindings();

src/main/java/frc/robot/subsystems/arm/ArmSubsystem.java

+10-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,12 @@
1515
import frc.robot.Constants.PivotConstants;
1616
import frc.robot.Constants.TelescopeConstants;
1717
import frc.robot.Constants.WristConstants;
18+
import frc.robot.subsystems.arm.pivot.Pivot;
19+
import frc.robot.subsystems.arm.pivot.PivotIO;
20+
import frc.robot.subsystems.arm.telescope.Telescope;
21+
import frc.robot.subsystems.arm.telescope.TelescopeIO;
22+
import frc.robot.subsystems.arm.wrist.Wrist;
23+
import frc.robot.subsystems.arm.wrist.WristIO;
1824

1925
public class ArmSubsystem extends SubsystemBase {
2026

@@ -59,18 +65,21 @@ public class ArmSubsystem extends SubsystemBase {
5965
new Color8Bit(Color.kCoral)));
6066

6167

62-
public ArmSubsystem() {
68+
public ArmSubsystem(PivotIO pivotIO, TelescopeIO telescopeIO, WristIO wristIO) {
6369
pivot = new Pivot(
70+
pivotIO,
6471
new TrapezoidProfile.Constraints(
6572
Units.degreesToRadians(360),
6673
Units.degreesToRadians(600)),
6774
() -> telescope.getPosition());
6875

6976
telescope = new Telescope(
77+
telescopeIO,
7078
new TrapezoidProfile.Constraints(3, 3),
7179
() -> pivot.getPosition());
7280

7381
wrist = new Wrist(
82+
wristIO,
7483
new TrapezoidProfile.Constraints(
7584
Units.degreesToRadians(630),
7685
Units.degreesToRadians(810)),

src/main/java/frc/robot/subsystems/arm/GenericArmJoint.java

+2-6
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ public void setSetpoint(double setpoint) {
4141
}
4242

4343
public void runControls() {
44-
update();
44+
updateInputs();
4545

4646
if (!active) {
4747
setOutput(0.0);
@@ -67,11 +67,7 @@ public void runControls() {
6767

6868
public abstract void setBrakeMode(boolean brake);
6969

70-
/**
71-
* Optional Override: Update internal state periodically
72-
*/
73-
protected void update() {
74-
}
70+
protected abstract void updateInputs();
7571

7672
/**
7773
* Set the control input to this joint, in volts

src/main/java/frc/robot/subsystems/arm/Pivot.java

-135
This file was deleted.

0 commit comments

Comments
 (0)