11package raidzero .robot .subsystems .telescopingarm ;
22
33import au .grapplerobotics .interfaces .LaserCanInterface .RangingMode ;
4- import au .grapplerobotics .interfaces .LaserCanInterface .RegionOfInterest ;
54import au .grapplerobotics .interfaces .LaserCanInterface .TimingBudget ;
65import com .ctre .phoenix6 .configs .TalonFXSConfiguration ;
76import com .ctre .phoenix6 .controls .Follower ;
87import com .ctre .phoenix6 .hardware .TalonFXS ;
98import com .ctre .phoenix6 .signals .InvertedValue ;
109import com .ctre .phoenix6 .signals .MotorArrangementValue ;
1110import com .ctre .phoenix6 .signals .NeutralModeValue ;
11+ import com .revrobotics .servohub .ServoChannel ;
12+ import com .revrobotics .servohub .ServoChannel .ChannelId ;
13+ import com .revrobotics .servohub .ServoHub ;
14+ import com .revrobotics .servohub .config .ServoChannelConfig .BehaviorWhenDisabled ;
15+ import com .revrobotics .servohub .config .ServoHubConfig ;
1216import edu .wpi .first .wpilibj2 .command .Command ;
1317import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
1418import raidzero .lib .LazyCan ;
1721public class CoralIntake extends SubsystemBase {
1822 private TalonFXS roller , follow ;
1923
24+ private ServoHub servoHub ;
25+ private ServoChannel intakeBlock ;
26+
2027 private LazyCan bottomLaser , topLaser ;
2128
2229 private static CoralIntake system ;
@@ -32,23 +39,22 @@ private CoralIntake() {
3239 follow .setControl (new Follower (Constants .TelescopingArm .Intake .MOTOR_ID , true ));
3340 follow .getConfigurator ().apply (followConfiguration ());
3441
35- bottomLaser = new LazyCan (0 );
36- try {
37- bottomLaser .setRangingMode (RangingMode .SHORT );
38- bottomLaser .setRegionOfInterest (new RegionOfInterest (8 , 4 , 6 , 8 ));
39- bottomLaser .setTimingBudget (TimingBudget .TIMING_BUDGET_20MS );
40- } catch (Exception e ) {
41- System .out .println ("LaserCan Config Error" );
42- }
42+ bottomLaser = new LazyCan (0 )
43+ .withRangingMode (RangingMode .SHORT )
44+ .withRegionOfInterest (8 , 4 , 6 , 8 )
45+ .withTimingBudget (TimingBudget .TIMING_BUDGET_20MS );
4346
44- topLaser = new LazyCan (1 );
45- try {
46- topLaser .setRangingMode (RangingMode .SHORT );
47- topLaser .setRegionOfInterest (new RegionOfInterest (8 , 4 , 6 , 8 ));
48- topLaser .setTimingBudget (TimingBudget .TIMING_BUDGET_20MS );
49- } catch (Exception e ) {
50- System .out .println ("LaserCan Config Error" );
51- }
47+ topLaser = new LazyCan (1 )
48+ .withRangingMode (RangingMode .SHORT )
49+ .withRegionOfInterest (8 , 4 , 6 , 8 )
50+ .withTimingBudget (TimingBudget .TIMING_BUDGET_20MS );
51+
52+ servoHub = new ServoHub (Constants .TelescopingArm .Intake .SERVO_HUB_ID );
53+ servoHub .configure (getServoHubConfig (), ServoHub .ResetMode .kResetSafeParameters );
54+
55+ intakeBlock = servoHub .getServoChannel (ChannelId .kChannelId2 );
56+ intakeBlock .setPowered (true );
57+ intakeBlock .setEnabled (true );
5258 }
5359
5460 /**
@@ -68,11 +74,7 @@ public TalonFXS getRoller() {
6874 */
6975 public Command intake () {
7076 return run (() -> roller .set (Constants .TelescopingArm .Intake .INTAKE_SPEED ))
71- .until (() -> getBottomLaserDistance () <= Constants .TelescopingArm .Intake .LASERCAN_DISTANCE_THRESHOLD_MM )
72- .andThen (
73- run (() -> roller .set (-Constants .TelescopingArm .Intake .INTAKE_SPEED ))
74- .withTimeout (0.1 )
75- );
77+ .until (() -> getBottomLaserDistance () <= Constants .TelescopingArm .Intake .LASERCAN_DISTANCE_THRESHOLD_MM );
7678 }
7779
7880 /**
@@ -81,10 +83,20 @@ public Command intake() {
8183 * @return A {@link Command} to scooch the coral upwards
8284 */
8385 public Command scoochCoral () {
84- return run (() -> roller .set (-Constants .TelescopingArm .Intake .INTAKE_SPEED ))
86+ return run (() -> roller .set (-Constants .TelescopingArm .Intake .INTAKE_LOWER_SPEED ))
8587 .until (() -> getTopLaserDistance () <= Constants .TelescopingArm .Intake .LASERCAN_DISTANCE_THRESHOLD_MM );
8688 }
8789
90+ /**
91+ * Creates a {@link Command} to move the coral upwards to unstuck the servo block
92+ *
93+ * @return A {@link Command} to move the coral upwards
94+ */
95+ public Command unstuckServo () {
96+ return run (() -> roller .set (-Constants .TelescopingArm .Intake .INTAKE_LOWER_SPEED ))
97+ .until (() -> getBottomLaserDistance () >= Constants .TelescopingArm .Intake .LASERCAN_DISTANCE_THRESHOLD_MM );
98+ }
99+
88100 /**
89101 * Creates a {@link Command} to stop the intake
90102 *
@@ -115,6 +127,15 @@ public Command run(double speed) {
115127 return run (() -> roller .set (speed ));
116128 }
117129
130+ @ Override
131+ public void periodic () {
132+ if (getBottomLaserDistance () > Constants .TelescopingArm .Intake .LASERCAN_DISTANCE_THRESHOLD_MM ) {
133+ intakeBlock .setPulseWidth (Constants .TelescopingArm .Intake .SERVO_EXTENDED );
134+ } else {
135+ intakeBlock .setPulseWidth (Constants .TelescopingArm .Intake .SERVO_RETRACTED );
136+ }
137+ }
138+
118139 /**
119140 * Gets the distance from the LaserCAN
120141 *
@@ -164,6 +185,25 @@ private TalonFXSConfiguration followConfiguration() {
164185 return configuration ;
165186 }
166187
188+ /**
189+ * Gets the {@link ServoHubConfig} for the REV Servo Hub
190+ *
191+ * @return The {@link ServoHubConfig} for the REV Servo Hub
192+ */
193+ private ServoHubConfig getServoHubConfig () {
194+ ServoHubConfig config = new ServoHubConfig ();
195+
196+ config .channel2
197+ .pulseRange (
198+ Constants .TelescopingArm .Intake .SERVO_EXTENDED ,
199+ Constants .TelescopingArm .Intake .SERVO_CENTER_WIDTH ,
200+ Constants .TelescopingArm .Intake .SERVO_RETRACTED
201+ )
202+ .disableBehavior (BehaviorWhenDisabled .kSupplyPower );
203+
204+ return config ;
205+ }
206+
167207 /**
168208 * Gets the {@link CoralIntake} subsystem instance
169209 *
0 commit comments