Skip to content

Commit 58a0c57

Browse files
authored
Safely disable subsystems (#131)
* I made sure that KidShampoo and Arm are safe to use without hardware/disabled * Made the Hoops outreach bot code hardware-insensitive * Added the LibFlip thing for Hoops and Ptechnodactyl * Removed some unused imports
1 parent 3c7d196 commit 58a0c57

File tree

8 files changed

+84
-37
lines changed

8 files changed

+84
-37
lines changed

Hoops/src/main/java/org/firstinspires/ftc/hoops/Hardware.java

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,15 +5,10 @@
55
import com.qualcomm.robotcore.hardware.DcMotorEx;
66
import com.qualcomm.robotcore.hardware.HardwareMap;
77
import com.technototes.library.hardware.motor.EncodedMotor;
8-
import com.technototes.library.hardware.motor.Motor;
98
import com.technototes.library.hardware.sensor.AdafruitIMU;
10-
import com.technototes.library.hardware.sensor.ColorDistanceSensor;
119
import com.technototes.library.hardware.sensor.IGyro;
1210
import com.technototes.library.hardware.sensor.IMU;
13-
import com.technototes.library.hardware.sensor.Rev2MDistanceSensor;
14-
import com.technototes.library.hardware.servo.Servo;
1511
import com.technototes.library.logger.Loggable;
16-
import com.technototes.vision.hardware.Webcam;
1712
import java.util.List;
1813
import org.firstinspires.ftc.robotcore.external.navigation.VoltageUnit;
1914

Hoops/src/main/java/org/firstinspires/ftc/hoops/subsystems/IntakeSubsystem.java

Lines changed: 34 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,30 +4,55 @@
44
import com.qualcomm.robotcore.hardware.DistanceSensor;
55
import com.technototes.library.hardware.motor.EncodedMotor;
66
import org.firstinspires.ftc.hoops.Hardware;
7+
import org.firstinspires.ftc.hoops.Setup;
8+
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
79

810
public class IntakeSubsystem {
911

12+
boolean hasHardware;
1013
EncodedMotor<DcMotorEx> slurp;
1114
DistanceSensor ballDetector;
1215

1316
public static double THE_VELOCITY = 0.5;
17+
public static double DISTANCE = 5.0;
1418

1519
public IntakeSubsystem(Hardware h) {
16-
slurp = h.slurp;
17-
slurp.coast();
18-
19-
//TODO: replace null with something
20-
21-
ballDetector = null;
20+
if (Setup.Connected.INTAKE) {
21+
hasHardware = true;
22+
slurp = h.slurp;
23+
slurp.coast();
24+
// TODO: replace null with something
25+
ballDetector = null;
26+
} else {
27+
hasHardware = false;
28+
ballDetector = null;
29+
slurp = null;
30+
}
2231
}
2332

2433
public void Intake(double angleInDegrees) {
25-
slurp.setVelocity(THE_VELOCITY);
34+
setSlurp(THE_VELOCITY);
2635
}
2736

2837
public void Stop() {
29-
slurp.setVelocity(0);
38+
setSlurp(0);
39+
}
40+
41+
public boolean Detect() {
42+
return getDistance() < DISTANCE;
3043
}
3144

32-
public void Detect() {}
45+
protected double getDistance() {
46+
if (hasHardware) {
47+
return ballDetector.getDistance(DistanceUnit.CM);
48+
} else {
49+
return 0;
50+
}
51+
}
52+
53+
protected void setSlurp(double val) {
54+
if (hasHardware) {
55+
slurp.setVelocity(val);
56+
}
57+
}
3358
}

Hoops/src/main/java/org/firstinspires/ftc/hoops/subsystems/LauncherSubsystem.java

Lines changed: 24 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -5,34 +5,48 @@
55
import com.qualcomm.robotcore.hardware.DcMotorSimple;
66
import com.technototes.library.hardware.motor.EncodedMotor;
77
import org.firstinspires.ftc.hoops.Hardware;
8+
import org.firstinspires.ftc.hoops.Setup;
89

910
@Config
1011
public class LauncherSubsystem {
1112

1213
public static double MAX_MOTOR_VELOCITY = 1.0;
1314

15+
boolean hasHardware;
16+
1417
EncodedMotor<DcMotorEx> top;
1518
EncodedMotor<DcMotorEx> bottom;
1619

1720
public LauncherSubsystem(Hardware h) {
1821
// Do stuff in here
19-
top = h.topLaunch;
20-
bottom = h.bottomLaunch;
21-
bottom.setDirection(DcMotorSimple.Direction.REVERSE);
22-
top.setDirection(DcMotorSimple.Direction.FORWARD);
23-
bottom.coast();
24-
top.coast();
22+
if (Setup.Connected.LAUNCHER) {
23+
hasHardware = true;
24+
top = h.topLaunch;
25+
bottom = h.bottomLaunch;
26+
bottom.setDirection(DcMotorSimple.Direction.REVERSE);
27+
top.setDirection(DcMotorSimple.Direction.FORWARD);
28+
bottom.coast();
29+
top.coast();
30+
} else {
31+
hasHardware = false;
32+
top = null;
33+
bottom = null;
34+
}
2535
}
2636

2737
public void Launch(double angleInDegrees) {
2838
// Spin the motors
2939
// TODO: make the motors spit the thing at the right angle
30-
top.setVelocity(MAX_MOTOR_VELOCITY);
31-
bottom.setVelocity(MAX_MOTOR_VELOCITY);
40+
if (hasHardware) {
41+
top.setVelocity(MAX_MOTOR_VELOCITY);
42+
bottom.setVelocity(MAX_MOTOR_VELOCITY);
43+
}
3244
}
3345

3446
public void Stop() {
35-
top.setVelocity(0);
36-
bottom.setVelocity(0);
47+
if (hasHardware) {
48+
top.setVelocity(0);
49+
bottom.setVelocity(0);
50+
}
3751
}
3852
}

Twenty403/src/main/java/org/firstinspires/ftc/twenty403/Hardware.java

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,20 +5,14 @@
55
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
66
import com.qualcomm.robotcore.hardware.DcMotorEx;
77
import com.qualcomm.robotcore.hardware.HardwareMap;
8-
import com.qualcomm.robotcore.hardware.ServoController;
98
import com.technototes.library.hardware.motor.CRServo;
109
import com.technototes.library.hardware.motor.EncodedMotor;
1110
import com.technototes.library.hardware.motor.Motor;
12-
import com.technototes.library.hardware.motor.Motor;
1311
import com.technototes.library.hardware.sensor.AdafruitIMU;
14-
import com.technototes.library.hardware.sensor.ColorSensor;
1512
import com.technototes.library.hardware.sensor.IGyro;
1613
import com.technototes.library.hardware.sensor.IMU;
17-
import com.technototes.library.hardware.sensor.Rev2MDistanceSensor;
18-
import com.technototes.library.hardware.sensor.encoder.MotorEncoder;
1914
import com.technototes.library.hardware.servo.Servo;
2015
import com.technototes.library.logger.Loggable;
21-
import com.technototes.vision.hardware.Webcam;
2216
import java.util.List;
2317
import org.firstinspires.ftc.robotcore.external.navigation.VoltageUnit;
2418
import org.firstinspires.ftc.twenty403.helpers.IEncoder;

Twenty403/src/main/java/org/firstinspires/ftc/twenty403/Robot.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,12 +49,16 @@ public Robot(Hardware hw, Alliance team, StartingPosition pos) {
4949
}
5050
if (Setup.Connected.KIDSSHAMPOOSUBSYSTEM) {
5151
this.kidShampooSubsystem = new KidShampooSubsystem(hw);
52+
} else {
53+
this.kidShampooSubsystem = new KidShampooSubsystem();
5254
}
5355
if (Setup.Connected.HANGSUBSYSTEM) {
5456
this.hangSubsystem = new HangSubsystem(hw);
5557
}
5658
if (Setup.Connected.ARMSUBSYSTEM) {
5759
this.armSubsystem = new ArmSubsystem(hw);
60+
} else {
61+
this.armSubsystem = new ArmSubsystem();
5862
}
5963
}
6064

Twenty403/src/main/java/org/firstinspires/ftc/twenty403/subsystems/ArmSubsystem.java

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -347,9 +347,11 @@ private void setSlideMotorPower(double speedSlide) {
347347
}
348348

349349
private void setArmMotorPower(double speed) {
350-
double clippedSpeed = Range.clip(speed, MIN_ARM_MOTOR_SPEED, MAX_ARM_MOTOR_SPEED);
351-
rotate1.setPower(clippedSpeed);
352-
rotate2.setPower(-clippedSpeed);
350+
if (isHardware) {
351+
double clippedSpeed = Range.clip(speed, MIN_ARM_MOTOR_SPEED, MAX_ARM_MOTOR_SPEED);
352+
rotate1.setPower(clippedSpeed);
353+
rotate2.setPower(-clippedSpeed);
354+
}
353355
}
354356

355357
public void horizontal() {

Twenty403/src/main/java/org/firstinspires/ftc/twenty403/subsystems/KidShampooSubsystem.java

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@ public class KidShampooSubsystem implements Subsystem, Loggable {
1414
private Servo retainer, jaw, wrist;
1515
private CRServo intake;
1616

17+
private boolean isHardware;
18+
1719
@Log(name = "jawPosition")
1820
public double jawPosition = 0;
1921

@@ -44,12 +46,21 @@ public class KidShampooSubsystem implements Subsystem, Loggable {
4446
public static double WRIST_STRAIGHT = .35;
4547

4648
public KidShampooSubsystem(Hardware hw) {
49+
isHardware = true;
4750
intake = hw.intake;
4851
retainer = hw.retainer;
4952
wrist = hw.wrist;
5053
jaw = hw.jaw;
5154
}
5255

56+
public KidShampooSubsystem() {
57+
isHardware = false;
58+
intake = null;
59+
retainer = null;
60+
wrist = null;
61+
jaw = null;
62+
}
63+
5364
public void openRetainer() {
5465
setRetainerPosition(RETAINER_OPEN_POSITION);
5566
}
@@ -114,28 +125,28 @@ public void stopIntake() {
114125
}
115126

116127
private void setRetainerPosition(double d) {
117-
if (retainer != null) {
128+
if (isHardware) {
118129
retainer.setPosition(d);
119130
retainerPos = d;
120131
}
121132
}
122133

123134
private void setJawPosition(double d) {
124-
if (jaw != null) {
135+
if (isHardware) {
125136
jaw.setPosition(d);
126137
jawPosition = d;
127138
}
128139
}
129140

130141
private void setIntakePower(double d) {
131-
if (intake != null) {
142+
if (isHardware) {
132143
intake.setPower(d);
133144
intakePow = d;
134145
}
135146
}
136147

137148
private void setWristPos(double w) {
138-
if (wrist != null) {
149+
if (isHardware) {
139150
//w = Range.clip(w, 0.0, 1.0);
140151
wrist.setPosition(w);
141152
wristPosition = w;

scripts/flip.ts

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@ const technoLib: FileList = {
3232
files: [
3333
'LearnBot/build.gradle',
3434
'Sixteen750/build.gradle',
35+
'Ptechnodactyl/build.gradle',
36+
'Hoops/build.gradle',
3537
'Twenty403/build.gradle',
3638
'build.dependencies.gradle',
3739
'settings.gradle',

0 commit comments

Comments
 (0)