Skip to content

Commit 69dda2a

Browse files
authored
Merge pull request #44 from TASRobotics/coralintake.cloos
Implement servo block on intake
2 parents 7f03aad + 55c3039 commit 69dda2a

File tree

4 files changed

+167
-27
lines changed

4 files changed

+167
-27
lines changed
Lines changed: 95 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,33 @@
11
package raidzero.lib;
22

3+
import au.grapplerobotics.ConfigurationFailedException;
34
import au.grapplerobotics.LaserCan;
5+
import au.grapplerobotics.interfaces.LaserCanInterface.Measurement;
6+
import au.grapplerobotics.interfaces.LaserCanInterface.RangingMode;
7+
import au.grapplerobotics.interfaces.LaserCanInterface.RegionOfInterest;
8+
import au.grapplerobotics.interfaces.LaserCanInterface.TimingBudget;
9+
import edu.wpi.first.wpilibj.DriverStation;
410

5-
public class LazyCan extends LaserCan {
11+
public class LazyCan {
12+
private LaserCan laserCan;
13+
private int canId;
14+
15+
private RangingMode rangingMode;
16+
private RegionOfInterest regionOfInterest;
17+
private TimingBudget timingBudget;
18+
19+
private Measurement measurement;
20+
21+
private double threshold;
622

723
/**
824
* Creates a new LaserCAN sensor.
925
*
1026
* @param canId The CAN ID for the LaserCAN sensor
1127
*/
1228
public LazyCan(int canId) {
13-
super(canId);
29+
laserCan = new LaserCan(canId);
30+
this.canId = canId;
1431
}
1532

1633
/**
@@ -19,8 +36,83 @@ public LazyCan(int canId) {
1936
* @return The distance in mm, -1 if the sensor cannot be found
2037
*/
2138
public int getDistanceMm() {
22-
Measurement measurement = getMeasurement();
39+
measurement = laserCan.getMeasurement();
2340

2441
return measurement != null ? measurement.distance_mm : -1;
2542
}
43+
44+
/**
45+
* Returns true if the LaserCan finds an object within the distance threshold
46+
*
47+
* @return if there is an object within the distance threshold
48+
*/
49+
public boolean withinThreshold() {
50+
measurement = laserCan.getMeasurement();
51+
52+
return measurement != null ? measurement.distance_mm <= threshold : false;
53+
}
54+
55+
/**
56+
* Sets the reigon of interest for the lasercan
57+
*
58+
* @param x the x start position for the reigon
59+
* @param y the y start position for the reigon
60+
* @param w the width of the reigon
61+
* @param h the height of the reigon
62+
* @return the current LazyCan Object
63+
*/
64+
public LazyCan withRegionOfInterest(int x, int y, int w, int h) {
65+
regionOfInterest = new RegionOfInterest(x, y, w, h);
66+
67+
try {
68+
laserCan.setRegionOfInterest(regionOfInterest);
69+
} catch (ConfigurationFailedException e) {
70+
DriverStation.reportError("LaserCan " + canId + ": RegionOfInterest Configuration failed! " + e, true);
71+
}
72+
73+
return this;
74+
}
75+
76+
/**
77+
* Sets the ranging mode of the LaserCan
78+
*
79+
* @param rangingMode the new ranging mode
80+
* @return the current LazyCan Object
81+
*/
82+
public LazyCan withRangingMode(RangingMode rangingMode) {
83+
this.rangingMode = rangingMode;
84+
try {
85+
laserCan.setRangingMode(rangingMode);
86+
} catch (ConfigurationFailedException e) {
87+
System.out.println("LaserCan " + canId + ": RangingMode Configuration failed! " + e);
88+
}
89+
return this;
90+
}
91+
92+
/**
93+
* Sets the timing budget of the LaserCan
94+
*
95+
* @param timingBudget the new timing budget
96+
* @return the current LazyCan Object
97+
*/
98+
public LazyCan withTimingBudget(TimingBudget timingBudget) {
99+
this.timingBudget = timingBudget;
100+
try {
101+
laserCan.setTimingBudget(timingBudget);
102+
} catch (ConfigurationFailedException e) {
103+
DriverStation.reportError("LaserCan " + canId + ": TimingBudget Configuration failed! " + e, true);
104+
}
105+
return this;
106+
}
107+
108+
/**
109+
* Sets the distance threshold of the LaserCan
110+
*
111+
* @param threshold the new threshold in milimeters
112+
* @return the current LazyCan object
113+
*/
114+
public LazyCan withThreshold(double threshold) {
115+
this.threshold = threshold;
116+
return this;
117+
}
26118
}

src/main/java/raidzero/robot/Constants.java

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,7 @@ public class Intake {
153153
public static final int MOTOR_ID = 12;
154154
public static final int FOLLOW_ID = 13;
155155

156-
public static final double INTAKE_SPEED = 0.08;
156+
public static final double INTAKE_SPEED = 0.25;
157157
public static final double INTAKE_LOWER_SPEED = 0.05;
158158

159159
public static final double EXTAKE_SPEED = 0.1;
@@ -162,6 +162,12 @@ public class Intake {
162162
public static final double LASERCAN_DISTANCE_THRESHOLD_MM = 50.0;
163163

164164
public static final int CURRENT_LIMIT = 25;
165+
166+
public static final int SERVO_HUB_ID = 3;
167+
168+
public static final int SERVO_RETRACTED = 1950;
169+
public static final int SERVO_EXTENDED = 1300;
170+
public static final int SERVO_CENTER_WIDTH = 1625;
165171
}
166172

167173
public class Joint {

src/main/java/raidzero/robot/RobotContainer.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,8 @@ private void configureBindings() {
177177
operator.button(Constants.Bindings.CORAL_INTAKE).onTrue(coralIntake.intake());
178178
operator.button(Constants.Bindings.CORAL_SCOOCH).onTrue(coralIntake.scoochCoral());
179179

180+
operator.button(Constants.Bindings.BOTTOM_RIGHT).onTrue(coralIntake.unstuckServo());
181+
180182
operator.button(Constants.Bindings.CLIMB_DEPLOY)
181183
.onTrue(
182184
Commands.waitSeconds(0.2)

src/main/java/raidzero/robot/subsystems/telescopingarm/CoralIntake.java

Lines changed: 63 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,18 @@
11
package raidzero.robot.subsystems.telescopingarm;
22

33
import au.grapplerobotics.interfaces.LaserCanInterface.RangingMode;
4-
import au.grapplerobotics.interfaces.LaserCanInterface.RegionOfInterest;
54
import au.grapplerobotics.interfaces.LaserCanInterface.TimingBudget;
65
import com.ctre.phoenix6.configs.TalonFXSConfiguration;
76
import com.ctre.phoenix6.controls.Follower;
87
import com.ctre.phoenix6.hardware.TalonFXS;
98
import com.ctre.phoenix6.signals.InvertedValue;
109
import com.ctre.phoenix6.signals.MotorArrangementValue;
1110
import 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;
1216
import edu.wpi.first.wpilibj2.command.Command;
1317
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1418
import raidzero.lib.LazyCan;
@@ -17,6 +21,9 @@
1721
public 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

Comments
 (0)