Skip to content

Commit db5a457

Browse files
authored
Merge pull request #25 from wmironpatriots/refactor/subsystems
Refactor/subsystems
2 parents 80b31be + 05e55bd commit db5a457

File tree

13 files changed

+480
-213
lines changed

13 files changed

+480
-213
lines changed
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.lib.subsystems;
8+
9+
// TODO FINISH CLASS
10+
public class RollerIONeo implements RollerIO {
11+
@Override
12+
public void periodic() {}
13+
14+
@Override
15+
public double getAppliedVolts() {
16+
return 0.0;
17+
}
18+
19+
@Override
20+
public double getSpeedRpm() {
21+
return 0.0;
22+
}
23+
24+
@Override
25+
public double getStatorCurrentAmps() {
26+
return 0.0;
27+
}
28+
29+
@Override
30+
public void setVolts(double volts) {}
31+
32+
@Override
33+
public void setSpeed(double speedRpm) {}
34+
35+
@Override
36+
public void close() throws Exception {}
37+
}
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.robot.subsystems.superstructure;
8+
9+
import static edu.wpi.first.units.Units.Centimeters;
10+
11+
import edu.wpi.first.epilogue.Logged;
12+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
13+
import org.frc6423.robot.subsystems.superstructure.arm.Arm;
14+
import org.frc6423.robot.subsystems.superstructure.elevator.Elevator;
15+
16+
public class Superstructure extends SubsystemBase {
17+
@Logged private final Elevator elevator = Elevator.create();
18+
@Logged private final Arm arm = Arm.create();
19+
20+
private final Visualizer visualizer = Visualizer.getInstance();
21+
22+
public Superstructure() {}
23+
24+
public void periodic() {
25+
/** Set visualizer poses */
26+
visualizer.setCarriageHeight(elevator.getCarriageHeight().in(Centimeters));
27+
visualizer.setStageHeight(elevator.getStageHeight().in(Centimeters));
28+
visualizer.setArmAngle(arm.getRotation2d());
29+
}
30+
}
Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,93 @@
1+
// Copyright (c) 2025 FRC 6423 - Ward Melville Iron Patriots
2+
// https://github.com/wmironpatriots
3+
//
4+
// Open Source Software; you can modify and/or share it under the terms of
5+
// MIT license file in the root directory of this project
6+
7+
package org.frc6423.robot.subsystems.superstructure;
8+
9+
import static edu.wpi.first.units.Units.Centimeters;
10+
import static org.frc6423.robot.subsystems.superstructure.arm.ArmPivot.*;
11+
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.MAX_EXTENSION_HEIGHT;
12+
13+
import edu.wpi.first.math.geometry.Rotation2d;
14+
import edu.wpi.first.units.measure.Distance;
15+
import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
16+
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
17+
import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d;
18+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
19+
import edu.wpi.first.wpilibj.util.Color;
20+
import edu.wpi.first.wpilibj.util.Color8Bit;
21+
22+
public class Visualizer {
23+
private static Visualizer instance;
24+
25+
/**
26+
* @return {@link Visualizer} singleton
27+
*/
28+
public static Visualizer getInstance() {
29+
if (instance == null) {
30+
instance = new Visualizer();
31+
}
32+
33+
return instance;
34+
}
35+
36+
private final Mechanism2d mech2d =
37+
new Mechanism2d(
38+
MAX_EXTENSION_HEIGHT.in(Centimeters), MAX_EXTENSION_HEIGHT.in(Centimeters) * 2 + 10);
39+
40+
// Elevator Roots
41+
private final MechanismRoot2d baseRoot =
42+
mech2d.getRoot("base", MAX_EXTENSION_HEIGHT.in(Centimeters) / 2, 0.0);
43+
private final MechanismRoot2d stageRoot =
44+
mech2d.getRoot("stageRoot", (MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 1, 0.0);
45+
private final MechanismRoot2d carriageRoot =
46+
mech2d.getRoot("carriageRoot", (MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 2, 0.0);
47+
48+
// Arm Ligament
49+
private final MechanismLigament2d arm;
50+
51+
private Visualizer() {
52+
// Setup elevator ligaments
53+
baseRoot.append(
54+
new MechanismLigament2d("base", 81.43936976, 90.0, 10.0, new Color8Bit(Color.kRed)));
55+
stageRoot.append(
56+
new MechanismLigament2d("stage", 83.82, 90.0, 7.0, new Color8Bit(Color.kYellow)));
57+
var carriageLig =
58+
carriageRoot.append(
59+
new MechanismLigament2d("carriage", 14.083, 90.0, 4.5, new Color8Bit(Color.kGreen)));
60+
61+
arm =
62+
carriageLig.append(
63+
new MechanismLigament2d(
64+
"arm", LENGTH.in(Centimeters), 0.0, 10, new Color8Bit(Color.kAliceBlue)));
65+
66+
SmartDashboard.putData("GlobalVisualizer", mech2d);
67+
}
68+
69+
public void setStageHeight(Distance height) {
70+
stageRoot.setPosition((MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 2, height.in(Centimeters));
71+
}
72+
73+
public void setCarriageHeight(Distance height) {
74+
carriageRoot.setPosition(
75+
(MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 4, height.in(Centimeters));
76+
}
77+
78+
public void setStageHeight(double heightCentimeters) {
79+
stageRoot.setPosition((MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 2, heightCentimeters);
80+
}
81+
82+
public void setCarriageHeight(double heightCentimeters) {
83+
carriageRoot.setPosition((MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 4, heightCentimeters);
84+
}
85+
86+
public void setArmAngle(Rotation2d angle) {
87+
arm.setAngle(angle.unaryMinus().plus(Rotation2d.kCCW_90deg));
88+
}
89+
90+
public void setArmAngle(double angleRads) {
91+
arm.setAngle(Rotation2d.fromRadians(angleRads).unaryMinus().plus(Rotation2d.kCCW_90deg));
92+
}
93+
}

src/main/java/org/frc6423/robot/subsystems/superstructure/arm/Arm.java

Lines changed: 104 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,14 +6,55 @@
66

77
package org.frc6423.robot.subsystems.superstructure.arm;
88

9+
import static edu.wpi.first.units.Units.RPM;
10+
import static edu.wpi.first.units.Units.Radians;
11+
912
import edu.wpi.first.epilogue.Logged;
13+
import edu.wpi.first.math.geometry.Rotation2d;
14+
import edu.wpi.first.units.measure.Angle;
15+
import edu.wpi.first.units.measure.AngularVelocity;
1016
import edu.wpi.first.wpilibj2.command.Command;
1117
import edu.wpi.first.wpilibj2.command.Commands;
1218
import edu.wpi.first.wpilibj2.command.SubsystemBase;
19+
import java.util.function.DoubleSupplier;
1320
import org.frc6423.lib.subsystems.RollerIO;
21+
import org.frc6423.lib.subsystems.RollerIONeo;
22+
import org.frc6423.lib.subsystems.RollerIONone;
23+
import org.frc6423.robot.Robot;
1424

1525
/** Arm Subsystem */
1626
public class Arm extends SubsystemBase {
27+
/** Represents a state the {@link Arm} subsystem can be in */
28+
// TODO CHECK ROLLER SPEEDS
29+
public static enum ArmState {
30+
/** Resting state */
31+
STOWED(Rotation2d.fromDegrees(90), 0.0),
32+
/** Avoidance state for preventing collisions */
33+
AVOIDING(Rotation2d.fromDegrees(65), 0.0),
34+
/** Flipped state for intaking */
35+
INTAKING(Rotation2d.fromDegrees(-90), 20.0),
36+
/** L2 pose but not scoring */
37+
L2_PRIMED(Rotation2d.fromDegrees(21.975), 0.0),
38+
/** L3 pose but not scoring */
39+
L3_PRIMED(Rotation2d.fromDegrees(21.975), 0.0),
40+
/** L4 pose but not scoring */
41+
L4_PRIMED(Rotation2d.fromDegrees(74.5), 0.0),
42+
/** L2 scoring */
43+
L2_SCORING(Rotation2d.fromDegrees(21.975), -40.0),
44+
/** L3 scoring */
45+
L3_SCORING(Rotation2d.fromDegrees(21.975), -40.0),
46+
/** L4 scoring */
47+
L4_SCORING(Rotation2d.fromDegrees(74.5), -40.0);
48+
49+
public final Rotation2d angle;
50+
public final double rollerSpeedRpm;
51+
52+
private ArmState(Rotation2d angle, double rollerSpeedRpm) {
53+
this.angle = angle;
54+
this.rollerSpeedRpm = rollerSpeedRpm;
55+
}
56+
}
57+
1758
@Logged(name = "Pivot Subsystem-Component")
1859
private final ArmPivot pivot;
1960

@@ -23,7 +64,27 @@ public class Arm extends SubsystemBase {
2364
@Logged(name = "Arm Setpoint State")
2465
private ArmState setpointState = ArmState.STOWED;
2566

26-
public Arm(ArmPivotIO pivotHardware, RollerIO rollerHardware) {
67+
/**
68+
* @return fake {@link Arm} subsystem
69+
*/
70+
public static Arm none() {
71+
return new Arm(new ArmPivotIONone(), new RollerIONone());
72+
}
73+
74+
/**
75+
* Factory for creating a {@link Arm} subsystem
76+
*
77+
* @return {@link Arm} Subsystem
78+
*/
79+
public static Arm create() {
80+
if (Robot.isReal()) {
81+
return new Arm(new ArmPivotIOReal(), new RollerIONeo());
82+
} else {
83+
return new Arm(new ArmPivotIOSim(), new RollerIONone());
84+
}
85+
}
86+
87+
private Arm(ArmPivotIO pivotHardware, RollerIO rollerHardware) {
2788
this.pivot = new ArmPivot(pivotHardware);
2889
this.roller = new ArmRoller(rollerHardware);
2990
}
@@ -38,6 +99,13 @@ public boolean isNearSetpointAngle() {
3899
return pivot.isNearSetpointAngle();
39100
}
40101

102+
/**
103+
* @return {@link Rotation2d} representing the arm angle
104+
*/
105+
public Rotation2d getRotation2d() {
106+
return pivot.getRotation2d();
107+
}
108+
41109
/**
42110
* @return true if arm has vectored coral piece
43111
*/
@@ -46,25 +114,51 @@ public boolean hasCoralVectored() {
46114
}
47115

48116
/**
49-
* Run arm to specified {@link ArmState}
117+
* Run arm to specified state
50118
*
51-
* @param state desired {@link ArmState}
119+
* @param pivotAngle {@link Angle} representing desired pivot angle
120+
* @param rollerSpeed {@link AngularVelocity} representing desired roller speed
52121
* @return {@link Command}
53122
*/
54-
public Command runState(ArmState state) {
123+
public Command runState(Angle pivotAngle, AngularVelocity rollerSpeed) {
55124
return Commands.parallel(
56-
this.run(() -> setpointState = state).until(() -> true),
57-
pivot.runAngle(state.angle.getMeasure()),
58-
roller.runSpeed(state.rollerSpeedRpm));
125+
this.run(() -> {}).until(() -> true),
126+
pivot.runAngle(pivotAngle.in(Radians)),
127+
roller.runSpeed(rollerSpeed.in(RPM)));
59128
}
60129

61130
/**
62-
* Hold arm at current angle and roller speed
131+
* Run arm to specified state
63132
*
133+
* @param pivotAngleRads desired pivot angle in radians
134+
* @param rollerSpeed desired roller speed in radians
64135
* @return {@link Command}
65136
*/
66-
public Command holdState() {
137+
public Command runState(DoubleSupplier pivotAngleRads, DoubleSupplier rollerSpeedRpm) {
67138
return Commands.parallel(
68-
this.run(() -> {}).until(() -> true), pivot.holdAngle(), roller.holdSpeed());
139+
this.run(() -> {}).until(() -> true),
140+
pivot.runAngle(pivotAngleRads.getAsDouble()),
141+
roller.runSpeed(rollerSpeedRpm.getAsDouble()));
142+
}
143+
144+
/**
145+
* Run arm to specified state
146+
*
147+
* @param pivotAngleRads desired pivot angle in radians
148+
* @param rollerSpeed desired roller speed in radians
149+
* @return {@link Command}
150+
*/
151+
public Command runState(double pivotAngleRads, double rollerSpeedRpm) {
152+
return this.runState(() -> pivotAngleRads, () -> rollerSpeedRpm);
153+
}
154+
155+
/**
156+
* Run arm to specified {@link ArmState}
157+
*
158+
* @param state desired {@link ArmState}
159+
* @return {@link Command}
160+
*/
161+
public Command runState(ArmState state) {
162+
return this.runState(state.angle.getRadians(), state.rollerSpeedRpm);
69163
}
70164
}

0 commit comments

Comments
 (0)