66
77package 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+
912import 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 ;
1016import edu .wpi .first .wpilibj2 .command .Command ;
1117import edu .wpi .first .wpilibj2 .command .Commands ;
1218import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
19+ import java .util .function .DoubleSupplier ;
1320import 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 */
1626public 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