Compare commits
117 Commits
aea3f0b2d4
...
SpindexerR
| Author | SHA1 | Date | |
|---|---|---|---|
| 51bf55cc49 | |||
| 6f3a178a08 | |||
| ccb52f625d | |||
| 8f92dc8f31 | |||
| 40d51ce757 | |||
| cfd09df8a0 | |||
| 59796154bd | |||
| d42af20447 | |||
| 1c292e77c7 | |||
| fde0880225 | |||
| e8bf2033ad | |||
| de6e7f2910 | |||
| ef5d615f91 | |||
| 4aca64f61c | |||
| bfcecd42d3 | |||
| 66e76285b2 | |||
| 7b923f31ca | |||
| d3bbbb7f2b | |||
| c160b3fa6b | |||
| de52f86280 | |||
| 58e7289c7b | |||
| 46ed4f544f | |||
| e39fa396cb | |||
| 5e8727ebaa | |||
| c460a4fb7a | |||
| 301b5ec765 | |||
| 70ad084ab1 | |||
| 70ca5b814a | |||
| d81a189ef9 | |||
| 82c3c83262 | |||
| b9e6dff3f8 | |||
| 8e8629f624 | |||
| d967e0489d | |||
| 16d9a13376 | |||
| 7f3ca719fa | |||
| 475fc4fe1c | |||
| 9c2a86c3e6 | |||
| d37bc733cf | |||
| 4588321b44 | |||
| 4b998766a1 | |||
| 07297c60f1 | |||
| 0bf392f81f | |||
| 05412940e8 | |||
| 054b6de169 | |||
| 75b3dc7fd4 | |||
| e3c259587e | |||
| b10a723f37 | |||
| ca37fa078c | |||
| ddc159ba3c | |||
| 713bafd9b4 | |||
| 61f314d71d | |||
| 1e87410d7b | |||
|
|
a7d1c18c56 | ||
| d5a3457be2 | |||
| 554204b6d4 | |||
| d586e3b4df | |||
| 2f5d4638ec | |||
| 1642e161c5 | |||
| 46a565c2c8 | |||
| a58371d3d7 | |||
| f48788cfd0 | |||
| 0838fc35f9 | |||
| 17643535ae | |||
| 5d93e3fc59 | |||
| fb8a4fae95 | |||
| b68f7eb6e7 | |||
| d1f658cb5b | |||
| 263bd46320 | |||
| 3f25463181 | |||
| 705eee180f | |||
| ef08883014 | |||
| 335e62ee3c | |||
| cdec64eb8f | |||
| fba9c7b114 | |||
| 873d0c5134 | |||
| 55dbfaaa98 | |||
| 0752c7c5f5 | |||
| 3440ff1783 | |||
| 0c3fd6fc83 | |||
| 8686b79314 | |||
| 03ae41c19b | |||
| e04c5fa830 | |||
| f9a220bf51 | |||
| 4b96775161 | |||
| 9a884885a9 | |||
| 36ac31b3ec | |||
| a1585e605f | |||
| 894a8d26fb | |||
| 09d82c1e02 | |||
| 62b6d1cf81 | |||
| c7f9028011 | |||
| 6b17bd4d46 | |||
| 695361e95c | |||
| be03468c19 | |||
| 6af717a629 | |||
| 74c4a5f144 | |||
| ba8c96ed89 | |||
| c3c68f8379 | |||
| 96d24a1010 | |||
| 0df43db6f0 | |||
| dc432f7686 | |||
| e89a659136 | |||
| 526bd62224 | |||
| 56820270c5 | |||
| 8f40bd50a8 | |||
| 238019d2ea | |||
| 4e5f0dd43d | |||
| a278fc0489 | |||
| 24473aeabb | |||
| 8d00c4dd0f | |||
| 4935b3332f | |||
| e64fa8e435 | |||
| 06e493aa2d | |||
| 846a0cccf3 | |||
| b3704556c4 | |||
| fe7d344420 | |||
| 6a584fe4ca |
@@ -23,6 +23,19 @@ android {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
repositories {
|
||||||
|
maven {
|
||||||
|
url = 'https://maven.brott.dev/'
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation project(':FtcRobotController')
|
implementation project(':FtcRobotController')
|
||||||
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
||||||
|
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
||||||
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
||||||
|
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
||||||
|
implementation 'org.ftclib.ftclib:core:2.1.1' // core
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,751 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoClose_V3 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
boolean gpp = false;
|
||||||
|
boolean pgp = false;
|
||||||
|
boolean ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
public static double holdTurrPow = 0.1; // power to hold turret in place
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !flywheel.getSteady();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
int id = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null && result.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
id = fiducial.getFiducialId();
|
||||||
|
TELE.addData("ID", id);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (id == 21){
|
||||||
|
gpp = true;
|
||||||
|
} else if (id == 22){
|
||||||
|
pgp = true;
|
||||||
|
} else if (id == 23){
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
if (redAlliance){
|
||||||
|
robot.limelight.pipelineSwitch(3);
|
||||||
|
double turretPID = turret_redClose;
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(-turretPID);
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.limelight.pipelineSwitch(2);
|
||||||
|
double turretPID = turret_blueClose;
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(-turretPID);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex(double spindexer, int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double spinPID = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (servo.spinEqual(spindexer)){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
robot.turr1.setPosition(holdTurrPow);
|
||||||
|
robot.turr2.setPosition(holdTurrPow);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = spindexer_intakePos1;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double pow = 1.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
robot.intake.setPower(pow);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (!servo.spinEqual(position)){
|
||||||
|
double spinPID = servo.setSpinPos(position);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
|
if (s2D > 60){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
} else if (s3D > 33){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
flywheel = new FlywheelV2();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
robot.limelight.pipelineSwitch(1);
|
||||||
|
robot.limelight.start();
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()){
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
}
|
||||||
|
|
||||||
|
double turrPID;
|
||||||
|
|
||||||
|
if (redAlliance){
|
||||||
|
turrPID = turret_detectRedClose;
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
} else {
|
||||||
|
turrPID = turret_detectBlueClose;
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turrPID);
|
||||||
|
robot.turr2.setPosition(-turrPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
bearing = result.getTx();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = turretPos;
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,651 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoFar_V1 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
boolean gpp = false;
|
||||||
|
boolean pgp = false;
|
||||||
|
boolean ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
public static double holdTurrPow = 0.1; // power to hold turret in place
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !flywheel.getSteady();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
int id = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null && result.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
id = fiducial.getFiducialId();
|
||||||
|
TELE.addData("ID", id);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (id == 21){
|
||||||
|
gpp = true;
|
||||||
|
} else if (id == 22){
|
||||||
|
pgp = true;
|
||||||
|
} else if (id == 23){
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
if (redAlliance){
|
||||||
|
robot.limelight.pipelineSwitch(3);
|
||||||
|
robot.turr1.setPosition(turret_redFar);
|
||||||
|
robot.turr2.setPosition(-turret_redFar);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.limelight.pipelineSwitch(2);
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turret_blueFar);
|
||||||
|
robot.turr2.setPosition(-turret_blueFar);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex(double spindexer, int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double spinPID = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (servo.spinEqual(spindexer)){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
robot.turr1.setPosition(holdTurrPow);
|
||||||
|
robot.turr2.setPosition(holdTurrPow);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = spindexer_intakePos1;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double pow = 1.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
robot.intake.setPower(pow);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (!servo.spinEqual(position)){
|
||||||
|
double spinPID = servo.setSpinPos(position);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
|
if (s2D > 60){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
} else if (s3D > 33){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
flywheel = new FlywheelV2();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
robot.limelight.pipelineSwitch(1);
|
||||||
|
robot.limelight.start();
|
||||||
|
|
||||||
|
//TODO: add positions to develop auto
|
||||||
|
|
||||||
|
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(0,0,0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rfx1, rfy1), rfh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()){
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
}
|
||||||
|
|
||||||
|
double turrPID;
|
||||||
|
|
||||||
|
if (redAlliance){
|
||||||
|
turrPID = turret_detectRedClose;
|
||||||
|
} else {
|
||||||
|
turrPID = turret_detectBlueClose;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turrPID);
|
||||||
|
robot.turr2.setPosition(-turrPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAutoFar);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
initShooter(AUTO_FAR_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(park.build());
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
bearing = result.getTx();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = turretPos;
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,802 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.by4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_blueClose;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_redClose;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.AUTO_CLOSE_VEL;
|
||||||
|
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinPow;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||||
|
public static double slowSpeed = 30.0;
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
Flywheel flywheel;
|
||||||
|
Servos servo;
|
||||||
|
double velo = 0.0;
|
||||||
|
boolean gpp = false;
|
||||||
|
boolean pgp = false;
|
||||||
|
boolean ppg = false;
|
||||||
|
public static double spinUnjamTime = 0.6;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
flywheel.manageFlywheel(vel);
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !flywheel.getSteady();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
int id = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null && result.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
id = fiducial.getFiducialId();
|
||||||
|
TELE.addData("ID", id);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (id == 21) {
|
||||||
|
gpp = true;
|
||||||
|
} else if (id == 22) {
|
||||||
|
pgp = true;
|
||||||
|
} else if (id == 23) {
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
if (redAlliance) {
|
||||||
|
robot.limelight.pipelineSwitch(3);
|
||||||
|
robot.turr1.setPosition(turret_redClose);
|
||||||
|
robot.turr2.setPosition(1 - turret_redClose);
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.limelight.pipelineSwitch(2);
|
||||||
|
double turretPID = turret_blueClose;
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(1 - turretPID);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex(double spindexer, int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double spinPID = 0.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
flywheel.manageFlywheel(vel);
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
|
||||||
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (servo.spinEqual(spindexer)) {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
int ticker = 1;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double finalPos = 0.0;
|
||||||
|
boolean zeroNeeded = false;
|
||||||
|
boolean zeroPassed = false;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double prevPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
flywheel.manageFlywheel(vel);
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(-0.3);
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 2.7) {
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
|
||||||
|
robot.spin1.setPower(-spinPow);
|
||||||
|
robot.spin2.setPower(spinPow);
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindexUnjam(double jamTime) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ticker % 12 < 6) {
|
||||||
|
|
||||||
|
robot.spin1.setPower(-1);
|
||||||
|
robot.spin2.setPower(1);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(1);
|
||||||
|
robot.spin2.setPower(-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (getRuntime() - stamp > jamTime+0.4) {
|
||||||
|
|
||||||
|
robot.intake.setPower(0.5);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
else if (getRuntime() - stamp > jamTime) {
|
||||||
|
|
||||||
|
robot.intake.setPower(-(getRuntime()-stamp-jamTime)*2.5);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
else {
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double spinCurrentPos = 0.0;
|
||||||
|
double spinInitPos = 0.0;
|
||||||
|
boolean reverse = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (ticker % 60 < 12) {
|
||||||
|
|
||||||
|
robot.spin1.setPower(-1);
|
||||||
|
robot.spin2.setPower(1);
|
||||||
|
|
||||||
|
} else if (ticker % 60 < 30) {
|
||||||
|
robot.spin1.setPower(-0.5);
|
||||||
|
robot.spin2.setPower(0.5);
|
||||||
|
}
|
||||||
|
else if (ticker % 60 < 42) {
|
||||||
|
robot.spin1.setPower(1);
|
||||||
|
robot.spin2.setPower(-1);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
robot.spin1.setPower(0.5);
|
||||||
|
robot.spin2.setPower(-0.5);
|
||||||
|
}
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
TELE.addData("Reverse?", reverse);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (getRuntime() - stamp > intakeTime) {
|
||||||
|
if (reverse) {
|
||||||
|
robot.spin1.setPower(-1);
|
||||||
|
robot.spin2.setPower(1);
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(1);
|
||||||
|
robot.spin2.setPower(-1);
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
if (ticker % 4 == 0) {
|
||||||
|
spinCurrentPos = servo.getSpinPos();
|
||||||
|
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
||||||
|
spinInitPos = spinCurrentPos;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
flywheel.manageFlywheel(vel);
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
|
||||||
|
robot.limelight.pipelineSwitch(1);
|
||||||
|
robot.limelight.start();
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
//
|
||||||
|
// TrajectoryActionBuilder lever = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
// .strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
TrajectoryActionBuilder shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()) {
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
double turretPID;
|
||||||
|
if (redAlliance) {
|
||||||
|
turretPID = turret_redClose;
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
|
||||||
|
// lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
// .strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup3 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx4a, ry4a), rh4a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
shoot3 = drive.actionBuilder(new Pose2d(rx4b, ry4b, rh4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
turretPID = turret_blueClose;
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turretPID);
|
||||||
|
robot.turr2.setPosition(1 - turretPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Red?", redAlliance);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
shoot1.build(),
|
||||||
|
spindexUnjam(spinUnjamTime)
|
||||||
|
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
spindexUnjam(spinUnjamTime)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup3.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot3.build(),
|
||||||
|
spindexUnjam(spinUnjamTime)
|
||||||
|
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
bearing = result.getTx();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
double turretPos = robot.turr1Pos.getCurrentPosition() - (bearing / 1300);
|
||||||
|
robot.turr1.setPosition(turretPos);
|
||||||
|
robot.turr2.setPosition(1 - turretPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addLine("Shooting");
|
||||||
|
TELE.update();
|
||||||
|
Actions.runBlocking(Shoot(AUTO_CLOSE_VEL));
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,4 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
public class blank {
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,5 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
public class Color {
|
||||||
|
public static boolean redAlliance = true;
|
||||||
|
}
|
||||||
@@ -0,0 +1,43 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class Poses {
|
||||||
|
|
||||||
|
public static double goalHeight = 42; //in inches
|
||||||
|
|
||||||
|
public static double turretHeight = 12;
|
||||||
|
|
||||||
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
|
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
|
public static double rx1 = 40, ry1 = -7, rh1 = 0;
|
||||||
|
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
||||||
|
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
||||||
|
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||||
|
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double bx1 = 40, by1 = 7, bh1 = 0;
|
||||||
|
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140);
|
||||||
|
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140);
|
||||||
|
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||||
|
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||||
|
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||||
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||||
|
|
||||||
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,45 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class ServoPositions {
|
||||||
|
|
||||||
|
public static double spindexer_intakePos1 = 0.39;
|
||||||
|
|
||||||
|
public static double spindexer_intakePos2 = 0.55;//0.5;
|
||||||
|
|
||||||
|
public static double spindexer_intakePos3 = 0.71;//0.66;
|
||||||
|
|
||||||
|
public static double spindexer_outtakeBall3 = 0.47;
|
||||||
|
|
||||||
|
public static double spindexer_outtakeBall2 = 0.31;
|
||||||
|
public static double spindexer_outtakeBall1 = 0.15;
|
||||||
|
|
||||||
|
public static double transferServo_out = 0.15;
|
||||||
|
|
||||||
|
public static double transferServo_in = 0.38;
|
||||||
|
|
||||||
|
public static double turret_range = 0.9;
|
||||||
|
|
||||||
|
public static double hoodDefault = 0.6;
|
||||||
|
|
||||||
|
public static double hoodAuto = 0.27;
|
||||||
|
|
||||||
|
public static double hoodAutoFar = 0.5; //TODO: change this;
|
||||||
|
|
||||||
|
public static double hoodHigh = 0.21; //TODO: change this;
|
||||||
|
|
||||||
|
public static double hoodLow = 1.0; //TODO: change this;
|
||||||
|
|
||||||
|
public static double turret_redClose = 0.42;
|
||||||
|
public static double turret_blueClose = 0.38;
|
||||||
|
public static double turret_redFar = 0.5; //TODO: change this
|
||||||
|
public static double turret_blueFar = 0.5; // TODO: change this
|
||||||
|
|
||||||
|
public static double turret_detectRedClose = 0.2;
|
||||||
|
|
||||||
|
public static double turret_detectBlueClose = 0.6;
|
||||||
|
public static double turrDefault = 0.4;
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,24 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class ShooterVars {
|
||||||
|
public static double turret_GearRatio = 0.9974;
|
||||||
|
|
||||||
|
public static double turret_Range = 355;
|
||||||
|
|
||||||
|
public static int velTolerance = 300;
|
||||||
|
|
||||||
|
public static int initTolerance = 1000;
|
||||||
|
|
||||||
|
public static int maxVel = 4500;
|
||||||
|
public static double waitTransferOut = 0.3;
|
||||||
|
public static double waitTransfer = 0.4;
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
|
||||||
|
// VELOCITY CONSTANTS
|
||||||
|
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
||||||
|
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||||
|
}
|
||||||
@@ -5,7 +5,9 @@ import androidx.annotation.NonNull;
|
|||||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
import com.acmerobotics.roadrunner.*;
|
import com.acmerobotics.roadrunner.AccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.Actions;
|
||||||
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
||||||
import com.acmerobotics.roadrunner.DualNum;
|
import com.acmerobotics.roadrunner.DualNum;
|
||||||
import com.acmerobotics.roadrunner.HolonomicController;
|
import com.acmerobotics.roadrunner.HolonomicController;
|
||||||
@@ -14,12 +16,20 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
|
|||||||
import com.acmerobotics.roadrunner.MotorFeedforward;
|
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.acmerobotics.roadrunner.Pose2dDual;
|
import com.acmerobotics.roadrunner.Pose2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||||
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.ProfileParams;
|
||||||
|
import com.acmerobotics.roadrunner.Rotation2d;
|
||||||
import com.acmerobotics.roadrunner.Time;
|
import com.acmerobotics.roadrunner.Time;
|
||||||
import com.acmerobotics.roadrunner.TimeTrajectory;
|
import com.acmerobotics.roadrunner.TimeTrajectory;
|
||||||
import com.acmerobotics.roadrunner.TimeTurn;
|
import com.acmerobotics.roadrunner.TimeTurn;
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
|
||||||
import com.acmerobotics.roadrunner.TurnConstraints;
|
import com.acmerobotics.roadrunner.TurnConstraints;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2d;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.VelConstraint;
|
import com.acmerobotics.roadrunner.VelConstraint;
|
||||||
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
||||||
import com.acmerobotics.roadrunner.ftc.Encoder;
|
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||||
@@ -34,6 +44,7 @@ import com.qualcomm.hardware.lynx.LynxModule;
|
|||||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
import com.qualcomm.robotcore.hardware.IMU;
|
import com.qualcomm.robotcore.hardware.IMU;
|
||||||
import com.qualcomm.robotcore.hardware.VoltageSensor;
|
import com.qualcomm.robotcore.hardware.VoltageSensor;
|
||||||
@@ -45,56 +56,15 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
|
|||||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
||||||
|
|
||||||
import java.lang.Math;
|
|
||||||
import java.util.Arrays;
|
import java.util.Arrays;
|
||||||
import java.util.LinkedList;
|
import java.util.LinkedList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
public final class MecanumDrive {
|
public final class MecanumDrive {
|
||||||
public static class Params {
|
|
||||||
// IMU orientation
|
|
||||||
// TODO: fill in these values based on
|
|
||||||
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
|
||||||
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
|
||||||
RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
|
||||||
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
|
||||||
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
|
|
||||||
|
|
||||||
// drive model parameters
|
|
||||||
public double inPerTick = 1;
|
|
||||||
public double lateralInPerTick = inPerTick;
|
|
||||||
public double trackWidthTicks = 0;
|
|
||||||
|
|
||||||
// feedforward parameters (in tick units)
|
|
||||||
public double kS = 0;
|
|
||||||
public double kV = 0;
|
|
||||||
public double kA = 0;
|
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
|
||||||
public double maxWheelVel = 50;
|
|
||||||
public double minProfileAccel = -30;
|
|
||||||
public double maxProfileAccel = 50;
|
|
||||||
|
|
||||||
// turn profile parameters (in radians)
|
|
||||||
public double maxAngVel = Math.PI; // shared with path
|
|
||||||
public double maxAngAccel = Math.PI;
|
|
||||||
|
|
||||||
// path controller gains
|
|
||||||
public double axialGain = 0.0;
|
|
||||||
public double lateralGain = 0.0;
|
|
||||||
public double headingGain = 0.0; // shared with turn
|
|
||||||
|
|
||||||
public double axialVelGain = 0.0;
|
|
||||||
public double lateralVelGain = 0.0;
|
|
||||||
public double headingVelGain = 0.0; // shared with turn
|
|
||||||
}
|
|
||||||
|
|
||||||
public static Params PARAMS = new Params();
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||||
|
|
||||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||||
public final VelConstraint defaultVelConstraint =
|
public final VelConstraint defaultVelConstraint =
|
||||||
@@ -104,20 +74,150 @@ public final class MecanumDrive {
|
|||||||
));
|
));
|
||||||
public final AccelConstraint defaultAccelConstraint =
|
public final AccelConstraint defaultAccelConstraint =
|
||||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||||
|
|
||||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||||
|
|
||||||
public final VoltageSensor voltageSensor;
|
public final VoltageSensor voltageSensor;
|
||||||
|
|
||||||
public final LazyImu lazyImu;
|
public final LazyImu lazyImu;
|
||||||
|
|
||||||
public final Localizer localizer;
|
public final Localizer localizer;
|
||||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||||
|
|
||||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||||
|
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||||
|
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||||
|
|
||||||
|
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||||
|
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: make sure your config has motors with these names (or change them)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||||
|
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||||
|
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||||
|
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||||
|
|
||||||
|
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
|
||||||
|
// TODO: reverse motor directions if needed
|
||||||
|
//
|
||||||
|
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||||
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
|
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||||
|
|
||||||
|
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setDrivePowers(PoseVelocity2d powers) {
|
||||||
|
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||||
|
PoseVelocity2dDual.constant(powers, 1));
|
||||||
|
|
||||||
|
double maxPowerMag = 1;
|
||||||
|
for (DualNum<Time> power : wheelVels.all()) {
|
||||||
|
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||||
|
}
|
||||||
|
|
||||||
|
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||||
|
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||||
|
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||||
|
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||||
|
}
|
||||||
|
|
||||||
|
public PoseVelocity2d updatePoseEstimate() {
|
||||||
|
PoseVelocity2d vel = localizer.update();
|
||||||
|
poseHistory.add(localizer.getPose());
|
||||||
|
|
||||||
|
while (poseHistory.size() > 100) {
|
||||||
|
poseHistory.removeFirst();
|
||||||
|
}
|
||||||
|
|
||||||
|
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||||
|
|
||||||
|
return vel;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void drawPoseHistory(Canvas c) {
|
||||||
|
double[] xPoints = new double[poseHistory.size()];
|
||||||
|
double[] yPoints = new double[poseHistory.size()];
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (Pose2d t : poseHistory) {
|
||||||
|
xPoints[i] = t.position.x;
|
||||||
|
yPoints[i] = t.position.y;
|
||||||
|
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
|
||||||
|
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||||
|
return new TrajectoryActionBuilder(
|
||||||
|
TurnAction::new,
|
||||||
|
FollowTrajectoryAction::new,
|
||||||
|
new TrajectoryBuilderParams(
|
||||||
|
1e-6,
|
||||||
|
new ProfileParams(
|
||||||
|
0.25, 0.1, 1e-2
|
||||||
|
)
|
||||||
|
),
|
||||||
|
beginPose, 0.0,
|
||||||
|
defaultTurnConstraints,
|
||||||
|
defaultVelConstraint, defaultAccelConstraint
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static class Params {
|
||||||
|
// IMU orientation
|
||||||
|
// TODO: fill in these values based on
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
||||||
|
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
||||||
|
RevHubOrientationOnRobot.LogoFacingDirection.RIGHT;
|
||||||
|
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
||||||
|
RevHubOrientationOnRobot.UsbFacingDirection.BACKWARD;
|
||||||
|
|
||||||
|
// drive model parameters
|
||||||
|
public double inPerTick = 0.001978956;
|
||||||
|
public double lateralInPerTick = 0.0013863732202094405;
|
||||||
|
public double trackWidthTicks = 6488.883015684446;
|
||||||
|
|
||||||
|
// feedforward parameters (in tick units)
|
||||||
|
public double kS = 1.2147826978829488;
|
||||||
|
public double kV = 0.00032;
|
||||||
|
public double kA = 0.000046;
|
||||||
|
|
||||||
|
// path profile parameters (in inches)
|
||||||
|
public double maxWheelVel = 180;
|
||||||
|
public double minProfileAccel = -40;
|
||||||
|
public double maxProfileAccel = 180;
|
||||||
|
|
||||||
|
// turn profile parameters (in radians)
|
||||||
|
public double maxAngVel = 4 * Math.PI; // shared with path
|
||||||
|
public double maxAngAccel = 4 * Math.PI;
|
||||||
|
|
||||||
|
// path controller gains
|
||||||
|
public double axialGain = 4;
|
||||||
|
public double lateralGain = 4;
|
||||||
|
public double headingGain = 4; // shared with turn
|
||||||
|
|
||||||
|
public double axialVelGain = 0.0;
|
||||||
|
public double lateralVelGain = 0.0;
|
||||||
|
public double headingVelGain = 0.0; // shared with turn
|
||||||
|
}
|
||||||
|
|
||||||
public class DriveLocalizer implements Localizer {
|
public class DriveLocalizer implements Localizer {
|
||||||
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
||||||
@@ -143,13 +243,13 @@ public final class MecanumDrive {
|
|||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void setPose(Pose2d pose) {
|
public Pose2d getPose() {
|
||||||
this.pose = pose;
|
return pose;
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public Pose2d getPose() {
|
public void setPose(Pose2d pose) {
|
||||||
return pose;
|
this.pose = pose;
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
@@ -215,60 +315,10 @@ public final class MecanumDrive {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
|
||||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
|
||||||
|
|
||||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
|
||||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO: make sure your config has motors with these names (or change them)
|
|
||||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
|
||||||
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
|
|
||||||
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
|
|
||||||
rightBack = hardwareMap.get(DcMotorEx.class, "rightBack");
|
|
||||||
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
|
|
||||||
|
|
||||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
|
|
||||||
// TODO: reverse motor directions if needed
|
|
||||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
|
|
||||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
|
||||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
|
||||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
|
||||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
|
||||||
|
|
||||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
|
||||||
|
|
||||||
localizer = new DriveLocalizer(pose);
|
|
||||||
|
|
||||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setDrivePowers(PoseVelocity2d powers) {
|
|
||||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
|
||||||
PoseVelocity2dDual.constant(powers, 1));
|
|
||||||
|
|
||||||
double maxPowerMag = 1;
|
|
||||||
for (DualNum<Time> power : wheelVels.all()) {
|
|
||||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
|
||||||
}
|
|
||||||
|
|
||||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
|
||||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
|
||||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
|
||||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
|
||||||
}
|
|
||||||
|
|
||||||
public final class FollowTrajectoryAction implements Action {
|
public final class FollowTrajectoryAction implements Action {
|
||||||
public final TimeTrajectory timeTrajectory;
|
public final TimeTrajectory timeTrajectory;
|
||||||
private double beginTs = -1;
|
|
||||||
|
|
||||||
private final double[] xPoints, yPoints;
|
private final double[] xPoints, yPoints;
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
public FollowTrajectoryAction(TimeTrajectory t) {
|
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||||
timeTrajectory = t;
|
timeTrajectory = t;
|
||||||
@@ -446,51 +496,4 @@ public final class MecanumDrive {
|
|||||||
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public PoseVelocity2d updatePoseEstimate() {
|
|
||||||
PoseVelocity2d vel = localizer.update();
|
|
||||||
poseHistory.add(localizer.getPose());
|
|
||||||
|
|
||||||
while (poseHistory.size() > 100) {
|
|
||||||
poseHistory.removeFirst();
|
|
||||||
}
|
|
||||||
|
|
||||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
|
||||||
|
|
||||||
|
|
||||||
return vel;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void drawPoseHistory(Canvas c) {
|
|
||||||
double[] xPoints = new double[poseHistory.size()];
|
|
||||||
double[] yPoints = new double[poseHistory.size()];
|
|
||||||
|
|
||||||
int i = 0;
|
|
||||||
for (Pose2d t : poseHistory) {
|
|
||||||
xPoints[i] = t.position.x;
|
|
||||||
yPoints[i] = t.position.y;
|
|
||||||
|
|
||||||
i++;
|
|
||||||
}
|
|
||||||
|
|
||||||
c.setStrokeWidth(1);
|
|
||||||
c.setStroke("#3F51B5");
|
|
||||||
c.strokePolyline(xPoints, yPoints);
|
|
||||||
}
|
|
||||||
|
|
||||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
|
||||||
return new TrajectoryActionBuilder(
|
|
||||||
TurnAction::new,
|
|
||||||
FollowTrajectoryAction::new,
|
|
||||||
new TrajectoryBuilderParams(
|
|
||||||
1e-6,
|
|
||||||
new ProfileParams(
|
|
||||||
0.25, 0.1, 1e-2
|
|
||||||
)
|
|
||||||
),
|
|
||||||
beginPose, 0.0,
|
|
||||||
defaultTurnConstraints,
|
|
||||||
defaultVelConstraint, defaultAccelConstraint
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,8 +16,8 @@ import java.util.Objects;
|
|||||||
@Config
|
@Config
|
||||||
public final class PinpointLocalizer implements Localizer {
|
public final class PinpointLocalizer implements Localizer {
|
||||||
public static class Params {
|
public static class Params {
|
||||||
public double parYTicks = 0.0; // y position of the parallel encoder (in tick units)
|
public double parYTicks = -3765.023079161767; // y position of the parallel encoder (in tick units)
|
||||||
public double perpXTicks = 0.0; // x position of the perpendicular encoder (in tick units)
|
public double perpXTicks = -1962.6377639490684; // x position of the perpendicular encoder (in tick units)
|
||||||
}
|
}
|
||||||
|
|
||||||
public static Params PARAMS = new Params();
|
public static Params PARAMS = new Params();
|
||||||
@@ -38,7 +38,7 @@ public final class PinpointLocalizer implements Localizer {
|
|||||||
driver.setOffsets(mmPerTick * PARAMS.parYTicks, mmPerTick * PARAMS.perpXTicks, DistanceUnit.MM);
|
driver.setOffsets(mmPerTick * PARAMS.parYTicks, mmPerTick * PARAMS.perpXTicks, DistanceUnit.MM);
|
||||||
|
|
||||||
// TODO: reverse encoder directions if needed
|
// TODO: reverse encoder directions if needed
|
||||||
initialParDirection = GoBildaPinpointDriver.EncoderDirection.FORWARD;
|
initialParDirection = GoBildaPinpointDriver.EncoderDirection.REVERSED;
|
||||||
initialPerpDirection = GoBildaPinpointDriver.EncoderDirection.FORWARD;
|
initialPerpDirection = GoBildaPinpointDriver.EncoderDirection.FORWARD;
|
||||||
|
|
||||||
driver.setEncoderDirections(initialParDirection, initialPerpDirection);
|
driver.setEncoderDirections(initialParDirection, initialPerpDirection);
|
||||||
|
|||||||
@@ -1,147 +1,130 @@
|
|||||||
# Team FTC Git Workflow Guide
|
## TeamCode Module
|
||||||
|
|
||||||
|
Welcome!
|
||||||
|
|
||||||
## 1. Cloning the Repository
|
This module, TeamCode, is the place where you will write/paste the code for your team's
|
||||||
|
robot controller App. This module is currently empty (a clean slate) but the
|
||||||
|
process for adding OpModes is straightforward.
|
||||||
|
|
||||||
1. Open a terminal (or the terminal inside Android Studio).
|
## Creating your own OpModes
|
||||||
2. Navigate to the folder where you want to keep the project.
|
|
||||||
3. Run:
|
|
||||||
|
|
||||||
```bash
|
The easiest way to create your own OpMode is to copy a Sample OpMode and make it your own.
|
||||||
git clone https://github.com/KeshavAnandCode/DecodeFTCMain.git
|
|
||||||
cd DecodeFTCMain
|
|
||||||
```
|
|
||||||
|
|
||||||
4. Verify your remotes:
|
Sample opmodes exist in the FtcRobotController module.
|
||||||
|
To locate these samples, find the FtcRobotController module in the "Project/Android" tab.
|
||||||
|
|
||||||
```bash
|
Expand the following tree elements:
|
||||||
git remote -v
|
FtcRobotController/java/org.firstinspires.ftc.robotcontroller/external/samples
|
||||||
```
|
|
||||||
|
|
||||||
You should see:
|
### Naming of Samples
|
||||||
```
|
|
||||||
origin https://github.com/KeshavAnandCode/DecodeFTCMain.git (fetch)
|
|
||||||
origin https://github.com/KeshavAnandCode/DecodeFTCMain.git (push)
|
|
||||||
upstream https://github.com/FIRST-Tech-Challenge/FtcRobotController.git (fetch)
|
|
||||||
upstream https://github.com/FIRST-Tech-Challenge/FtcRobotController.git (push)
|
|
||||||
```
|
|
||||||
|
|
||||||
---
|
To gain a better understanding of how the samples are organized, and how to interpret the
|
||||||
|
naming system, it will help to understand the conventions that were used during their creation.
|
||||||
|
|
||||||
## 2. Keeping `master` Clean
|
These conventions are described (in detail) in the sample_conventions.md file in this folder.
|
||||||
|
|
||||||
- `master` should only contain clean, tested code.
|
To summarize: A range of different samples classes will reside in the java/external/samples.
|
||||||
- Nobody should ever code directly on `master`.
|
The class names will follow a naming convention which indicates the purpose of each class.
|
||||||
- To stay up to date:
|
The prefix of the name will be one of the following:
|
||||||
|
|
||||||
```bash
|
Basic: This is a minimally functional OpMode used to illustrate the skeleton/structure
|
||||||
git checkout master
|
of a particular style of OpMode. These are bare bones examples.
|
||||||
git fetch upstream
|
|
||||||
git merge upstream/master
|
|
||||||
git push origin master
|
|
||||||
```
|
|
||||||
|
|
||||||
---
|
Sensor: This is a Sample OpMode that shows how to use a specific sensor.
|
||||||
|
It is not intended to drive a functioning robot, it is simply showing the minimal code
|
||||||
|
required to read and display the sensor values.
|
||||||
|
|
||||||
## 3. Creating a Feature Branch
|
Robot: This is a Sample OpMode that assumes a simple two-motor (differential) drive base.
|
||||||
|
It may be used to provide a common baseline driving OpMode, or
|
||||||
|
to demonstrate how a particular sensor or concept can be used to navigate.
|
||||||
|
|
||||||
Whenever you start a new task (feature, fix, experiment):
|
Concept: This is a sample OpMode that illustrates performing a specific function or concept.
|
||||||
|
These may be complex, but their operation should be explained clearly in the comments,
|
||||||
|
or the comments should reference an external doc, guide or tutorial.
|
||||||
|
Each OpMode should try to only demonstrate a single concept so they are easy to
|
||||||
|
locate based on their name. These OpModes may not produce a drivable robot.
|
||||||
|
|
||||||
1. Update `master` (see above).
|
After the prefix, other conventions will apply:
|
||||||
2. Create a new branch from `master`:
|
|
||||||
|
|
||||||
```bash
|
* Sensor class names are constructed as: Sensor - Company - Type
|
||||||
git checkout master
|
* Robot class names are constructed as: Robot - Mode - Action - OpModetype
|
||||||
git pull origin master
|
* Concept class names are constructed as: Concept - Topic - OpModetype
|
||||||
git checkout -b feature/short-description
|
|
||||||
```
|
|
||||||
|
|
||||||
### Branch Naming Standard
|
Once you are familiar with the range of samples available, you can choose one to be the
|
||||||
|
basis for your own robot. In all cases, the desired sample(s) needs to be copied into
|
||||||
|
your TeamCode module to be used.
|
||||||
|
|
||||||
Branches **must** follow the format:
|
This is done inside Android Studio directly, using the following steps:
|
||||||
|
|
||||||
|
1) Locate the desired sample class in the Project/Android tree.
|
||||||
|
|
||||||
|
2) Right click on the sample class and select "Copy"
|
||||||
|
|
||||||
|
3) Expand the TeamCode/java folder
|
||||||
|
|
||||||
|
4) Right click on the org.firstinspires.ftc.teamcode folder and select "Paste"
|
||||||
|
|
||||||
|
5) You will be prompted for a class name for the copy.
|
||||||
|
Choose something meaningful based on the purpose of this class.
|
||||||
|
Start with a capital letter, and remember that there may be more similar classes later.
|
||||||
|
|
||||||
|
Once your copy has been created, you should prepare it for use on your robot.
|
||||||
|
This is done by adjusting the OpMode's name, and enabling it to be displayed on the
|
||||||
|
Driver Station's OpMode list.
|
||||||
|
|
||||||
|
Each OpMode sample class begins with several lines of code like the ones shown below:
|
||||||
|
|
||||||
```
|
```
|
||||||
<type>/<short-description>
|
@TeleOp(name="Template: Linear OpMode", group="Linear Opmode")
|
||||||
|
@Disabled
|
||||||
```
|
```
|
||||||
|
|
||||||
Where `<type>` is one of:
|
The name that will appear on the driver station's "opmode list" is defined by the code:
|
||||||
- `feature/` → new functionality
|
``name="Template: Linear OpMode"``
|
||||||
- `fix/` → bug fixes
|
You can change what appears between the quotes to better describe your opmode.
|
||||||
- `experiment/` → prototypes or tests
|
The "group=" portion of the code can be used to help organize your list of OpModes.
|
||||||
- `docs/` → documentation updates
|
|
||||||
- `chore/` → maintenance or cleanup
|
|
||||||
|
|
||||||
Examples:
|
As shown, the current OpMode will NOT appear on the driver station's OpMode list because of the
|
||||||
- `feature/autonomous-path`
|
``@Disabled`` annotation which has been included.
|
||||||
- `fix/motor-init`
|
This line can simply be deleted , or commented out, to make the OpMode visible.
|
||||||
- `experiment/vision-test`
|
|
||||||
- `docs/setup-instructions`
|
|
||||||
- `chore/gradle-update`
|
|
||||||
|
|
||||||
**Rules for names:**
|
## ADVANCED Multi-Team App management: Cloning the TeamCode Module
|
||||||
- Use lowercase letters and hyphens (`-`) only.
|
|
||||||
- Keep it short but clear (3–5 words).
|
|
||||||
- One branch = one task. Never mix unrelated work.
|
|
||||||
|
|
||||||
---
|
In some situations, you have multiple teams in your club and you want them to all share
|
||||||
|
a common code organization, with each being able to *see* the others code but each having
|
||||||
|
their own team module with their own code that they maintain themselves.
|
||||||
|
|
||||||
## 4. Working on Your Branch
|
In this situation, you might wish to clone the TeamCode module, once for each of these teams.
|
||||||
|
Each of the clones would then appear along side each other in the Android Studio module list,
|
||||||
|
together with the FtcRobotController module (and the original TeamCode module).
|
||||||
|
|
||||||
- Make changes in Android Studio.
|
Selective Team phones can then be programmed by selecting the desired Module from the pulldown list
|
||||||
- Stage and commit your changes:
|
prior to clicking to the green Run arrow.
|
||||||
|
|
||||||
```bash
|
Warning: This is not for the inexperienced Software developer.
|
||||||
git add .
|
You will need to be comfortable with File manipulations and managing Android Studio Modules.
|
||||||
git commit -m "short message about what changed"
|
These changes are performed OUTSIDE of Android Studios, so close Android Studios before you do this.
|
||||||
```
|
|
||||||
|
|
||||||
- Push your branch to GitHub:
|
Also.. Make a full project backup before you start this :)
|
||||||
|
|
||||||
```bash
|
To clone TeamCode, do the following:
|
||||||
git push origin feature/short-description
|
|
||||||
```
|
|
||||||
|
|
||||||
---
|
Note: Some names start with "Team" and others start with "team". This is intentional.
|
||||||
|
|
||||||
## 5. Sharing Your Work
|
1) Using your operating system file management tools, copy the whole "TeamCode"
|
||||||
|
folder to a sibling folder with a corresponding new name, eg: "Team0417".
|
||||||
|
|
||||||
- Once your branch is ready:
|
2) In the new Team0417 folder, delete the TeamCode.iml file.
|
||||||
1. Open a Pull Request (PR) on GitHub to merge into `master`.
|
|
||||||
2. At least one teammate should review before merging.
|
|
||||||
|
|
||||||
---
|
3) the new Team0417 folder, rename the "src/main/java/org/firstinspires/ftc/teamcode" folder
|
||||||
|
to a matching name with a lowercase 'team' eg: "team0417".
|
||||||
|
|
||||||
## 6. Branching Rules
|
4) In the new Team0417/src/main folder, edit the "AndroidManifest.xml" file, change the line that
|
||||||
|
contains
|
||||||
|
package="org.firstinspires.ftc.teamcode"
|
||||||
|
to be
|
||||||
|
package="org.firstinspires.ftc.team0417"
|
||||||
|
|
||||||
**Do:**
|
5) Add: include ':Team0417' to the "/settings.gradle" file.
|
||||||
- Always branch from `master`.
|
|
||||||
- Follow the naming standard exactly.
|
|
||||||
- Keep branches small and focused.
|
|
||||||
- Delete branches after they’re merged.
|
|
||||||
|
|
||||||
**Don’t:**
|
6) Open up Android Studios and clean out any old files by using the menu to "Build/Clean Project""
|
||||||
- Don’t push commits directly to `master`.
|
|
||||||
- Don’t leave unfinished work on `master`.
|
|
||||||
- Don’t mix unrelated changes in one branch.
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
## 7. Example Workflow
|
|
||||||
|
|
||||||
```bash
|
|
||||||
# Get latest code
|
|
||||||
git checkout master
|
|
||||||
git fetch upstream
|
|
||||||
git merge upstream/master
|
|
||||||
git push origin master
|
|
||||||
|
|
||||||
# Start a new feature
|
|
||||||
git checkout -b feature/teleop-improvements
|
|
||||||
|
|
||||||
# Work on code, then commit
|
|
||||||
git add .
|
|
||||||
git commit -m "improved joystick scaling in TeleOp"
|
|
||||||
|
|
||||||
# Push branch
|
|
||||||
git push origin feature/teleop-improvements
|
|
||||||
```
|
|
||||||
@@ -0,0 +1,896 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class TeleopV2 extends LinearOpMode {
|
||||||
|
Servos servo;
|
||||||
|
Flywheel flywheel;
|
||||||
|
public static double manualVel = 3000;
|
||||||
|
public static double hood = 0.5;
|
||||||
|
public static double hoodDefaultPos = 0.5;
|
||||||
|
public static double desiredTurretAngle = 180;
|
||||||
|
public static double velMultiplier = 20;
|
||||||
|
public static double shootStamp2 = 0.0;
|
||||||
|
|
||||||
|
public double vel = 3000;
|
||||||
|
public boolean autoVel = true;
|
||||||
|
public double manualOffset = 0.0;
|
||||||
|
public boolean autoHood = true;
|
||||||
|
public boolean green1 = false;
|
||||||
|
public boolean green2 = false;
|
||||||
|
public boolean green3 = false;
|
||||||
|
public double shootStamp = 0.0;
|
||||||
|
public boolean circle = false;
|
||||||
|
public boolean square = false;
|
||||||
|
public boolean triangle = false;
|
||||||
|
double autoHoodOffset = 0.0;
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
boolean intake = false;
|
||||||
|
boolean reject = false;
|
||||||
|
double xOffset = 0.0;
|
||||||
|
double yOffset = 0.0;
|
||||||
|
double headingOffset = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
int camTicker = 0;
|
||||||
|
List<Double> s1G = new ArrayList<>();
|
||||||
|
List<Double> s2G = new ArrayList<>();
|
||||||
|
List<Double> s3G = new ArrayList<>();
|
||||||
|
List<Double> s1T = new ArrayList<>();
|
||||||
|
List<Double> s2T = new ArrayList<>();
|
||||||
|
List<Double> s3T = new ArrayList<>();
|
||||||
|
List<Boolean> s1 = new ArrayList<>();
|
||||||
|
List<Boolean> s2 = new ArrayList<>();
|
||||||
|
List<Boolean> s3 = new ArrayList<>();
|
||||||
|
boolean oddBallColor = false;
|
||||||
|
AprilTagWebcam aprilTagWebcam = new AprilTagWebcam();
|
||||||
|
MecanumDrive drive;
|
||||||
|
double hoodOffset = 0.0;
|
||||||
|
boolean shoot1 = false;
|
||||||
|
// Make these class-level flags
|
||||||
|
boolean shootA = true;
|
||||||
|
boolean shootB = true;
|
||||||
|
boolean shootC = true;
|
||||||
|
boolean manualTurret = false;
|
||||||
|
|
||||||
|
boolean outtake1 = false;
|
||||||
|
boolean outtake2 = false;
|
||||||
|
boolean outtake3 = false;
|
||||||
|
boolean overrideTurr = false;
|
||||||
|
|
||||||
|
List<Integer> shootOrder = new ArrayList<>();
|
||||||
|
boolean emergency = false;
|
||||||
|
private double lastEncoderRevolutions = 0.0;
|
||||||
|
private double lastTimeStamp = 0.0;
|
||||||
|
private double velo1, velo;
|
||||||
|
private double stamp1, stamp, initPos;
|
||||||
|
private boolean shootAll = false;
|
||||||
|
private double transferStamp = 0.0;
|
||||||
|
private int tickerA = 1;
|
||||||
|
private boolean transferIn = false;
|
||||||
|
double turretPID = 0.0;
|
||||||
|
double turretPos = 0.5;
|
||||||
|
double spindexPID = 0.0;
|
||||||
|
double spindexPos = spindexer_intakePos1;
|
||||||
|
double error = 0.0;
|
||||||
|
|
||||||
|
public static double velPrediction(double distance) {
|
||||||
|
|
||||||
|
if (distance < 30) {
|
||||||
|
return 2750;
|
||||||
|
} else if (distance > 100) {
|
||||||
|
if (distance > 160) {
|
||||||
|
return 4200;
|
||||||
|
}
|
||||||
|
return 3700;
|
||||||
|
} else {
|
||||||
|
// linear interpolation between 40->2650 and 120->3600
|
||||||
|
double slope = (3700.0 - 2750.0) / (100.0 - 30);
|
||||||
|
return (int) Math.round(2750 + slope * (distance - 30));
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||||
|
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
Pose2d shootPos = teleStart;
|
||||||
|
|
||||||
|
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
//DRIVETRAIN:
|
||||||
|
|
||||||
|
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
||||||
|
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
||||||
|
double rx = gamepad1.left_stick_x;
|
||||||
|
|
||||||
|
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||||
|
double frontLeftPower = (y + x + rx) / denominator;
|
||||||
|
double backLeftPower = (y - x + rx) / denominator;
|
||||||
|
double frontRightPower = (y - x - rx) / denominator;
|
||||||
|
double backRightPower = (y + x - rx) / denominator;
|
||||||
|
|
||||||
|
robot.frontLeft.setPower(frontLeftPower);
|
||||||
|
robot.backLeft.setPower(backLeftPower);
|
||||||
|
robot.frontRight.setPower(frontRightPower);
|
||||||
|
robot.backRight.setPower(backRightPower);
|
||||||
|
|
||||||
|
|
||||||
|
//TODO: make sure changing position works throughout opmode
|
||||||
|
if (!servo.spinEqual(spindexPos)){
|
||||||
|
spindexPID = servo.setSpinPos(spindexPos);
|
||||||
|
robot.spin1.setPower(spindexPID);
|
||||||
|
robot.spin2.setPower(-spindexPID);
|
||||||
|
} else{
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
//INTAKE:
|
||||||
|
|
||||||
|
if (gamepad1.rightBumperWasPressed()) {
|
||||||
|
intake = !intake;
|
||||||
|
reject = false;
|
||||||
|
shootAll = false;
|
||||||
|
emergency = false;
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad1.leftBumperWasPressed()) {
|
||||||
|
intake = false;
|
||||||
|
emergency = !emergency;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake) {
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
spindexPos = spindexer_intakePos1 + 0.015;
|
||||||
|
} else {
|
||||||
|
spindexPos = spindexer_intakePos1 - 0.015;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (reject) {
|
||||||
|
robot.intake.setPower(-1);
|
||||||
|
spindexPos = spindexer_intakePos1;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
//COLOR:
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (s1D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s1G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s1.add(true);
|
||||||
|
} else {
|
||||||
|
s1.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s1T.add(getRuntime());
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s2G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s2.add(true);
|
||||||
|
} else {
|
||||||
|
s2.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s2T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 30) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s3G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s3.add(true);
|
||||||
|
} else {
|
||||||
|
s3.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s3T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!s1.isEmpty()) {
|
||||||
|
green1 = checkGreen(s1, s1T);
|
||||||
|
}
|
||||||
|
if (!s2.isEmpty()) {
|
||||||
|
green2 = checkGreen(s2, s2T);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (!s3.isEmpty()) {
|
||||||
|
green3 = checkGreen(s3, s3T);
|
||||||
|
}
|
||||||
|
|
||||||
|
//SHOOTER:
|
||||||
|
|
||||||
|
double powPID = flywheel.manageFlywheel((int) vel);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
//TURRET:
|
||||||
|
|
||||||
|
double offset;
|
||||||
|
|
||||||
|
double robX = drive.localizer.getPose().position.x;
|
||||||
|
double robY = drive.localizer.getPose().position.y;
|
||||||
|
|
||||||
|
double robotX = robX - xOffset;
|
||||||
|
double robotY = robY - yOffset;
|
||||||
|
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||||
|
|
||||||
|
double goalX = -10;
|
||||||
|
double goalY = 0;
|
||||||
|
|
||||||
|
double dx = goalX - robotX; // delta x from robot to goal
|
||||||
|
double dy = goalY - robotY; // delta y from robot to goal
|
||||||
|
|
||||||
|
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
|
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
||||||
|
|
||||||
|
desiredTurretAngle += manualOffset;
|
||||||
|
|
||||||
|
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||||
|
|
||||||
|
if (offset > 135) {
|
||||||
|
offset -= 360;
|
||||||
|
}
|
||||||
|
|
||||||
|
//TODO: test the camera teleop code
|
||||||
|
double pos = turrDefault + (error/8); // adds the overall error to the default
|
||||||
|
|
||||||
|
TELE.addData("offset", offset);
|
||||||
|
|
||||||
|
pos -= offset * (0.9 / 360);
|
||||||
|
|
||||||
|
if (pos < 0.02) {
|
||||||
|
pos = 0.02;
|
||||||
|
} else if (pos > 0.97) {
|
||||||
|
pos = 0.97;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1){ //not moving
|
||||||
|
AprilTagDetection d20 = aprilTagWebcam.getTagById(20);
|
||||||
|
AprilTagDetection d24 = aprilTagWebcam.getTagById(24);
|
||||||
|
|
||||||
|
double bearing = 0.0;
|
||||||
|
if (d20 != null || d24 != null){
|
||||||
|
if (d20 != null) {
|
||||||
|
bearing = d20.ftcPose.bearing;
|
||||||
|
}
|
||||||
|
if (d24 != null) {
|
||||||
|
bearing = d24.ftcPose.bearing;
|
||||||
|
}
|
||||||
|
overrideTurr = true;
|
||||||
|
turretPos = servo.getTurrPos() - (bearing/1300);
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
|
||||||
|
double bearingCorrection = bearing / 1300;
|
||||||
|
|
||||||
|
|
||||||
|
// deadband: ignore tiny noise
|
||||||
|
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
||||||
|
|
||||||
|
// only accumulate if bearing direction is consistent
|
||||||
|
if (Math.signum(bearingCorrection) == Math.signum(error) || error == 0) {
|
||||||
|
error += bearingCorrection;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
camTicker++;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
} else {
|
||||||
|
camTicker = 0;
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (manualTurret) {
|
||||||
|
pos = turrDefault + (manualOffset / 100);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!overrideTurr) {
|
||||||
|
turretPos = pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpad_right) {
|
||||||
|
manualOffset -= 2;
|
||||||
|
} else if (gamepad2.dpad_left) {
|
||||||
|
manualOffset += 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
//VELOCITY AUTOMATIC
|
||||||
|
|
||||||
|
if (autoVel) {
|
||||||
|
vel = velPrediction(distanceToGoal);
|
||||||
|
} else {
|
||||||
|
vel = manualVel;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.right_stick_button) {
|
||||||
|
autoVel = true;
|
||||||
|
} else if (gamepad2.right_stick_y < -0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 4100;
|
||||||
|
} else if (gamepad2.right_stick_y > 0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 2700;
|
||||||
|
} else if (gamepad2.right_stick_x > 0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 3600;
|
||||||
|
} else if (gamepad2.right_stick_x < -0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 3100;
|
||||||
|
}
|
||||||
|
|
||||||
|
//HOOD:
|
||||||
|
|
||||||
|
if (autoHood) {
|
||||||
|
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
||||||
|
} else {
|
||||||
|
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodOffset -= 0.03;
|
||||||
|
autoHoodOffset -= 0.02;
|
||||||
|
|
||||||
|
} else if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodOffset += 0.03;
|
||||||
|
autoHoodOffset += 0.02;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_x > 0.5) {
|
||||||
|
manualTurret = false;
|
||||||
|
} else if (gamepad2.left_stick_x < -0.5) {
|
||||||
|
manualOffset = 0;
|
||||||
|
manualTurret = false;
|
||||||
|
if (gamepad2.left_bumper) {
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(2, 0, 0));
|
||||||
|
sleep(1200);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_y < -0.5) {
|
||||||
|
autoHood = true;
|
||||||
|
} else if (gamepad2.left_stick_y > 0.5) {
|
||||||
|
autoHood = false;
|
||||||
|
hoodOffset = 0;
|
||||||
|
if (gamepad2.left_bumper) {
|
||||||
|
xOffset = robotX;
|
||||||
|
yOffset = robotY;
|
||||||
|
headingOffset = robotHeading;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//SHOOT ALL:]
|
||||||
|
|
||||||
|
if (emergency) {
|
||||||
|
intake = false;
|
||||||
|
reject = true;
|
||||||
|
|
||||||
|
if (getRuntime() % 3 > 1.5) {
|
||||||
|
spindexPos = 1;
|
||||||
|
} else {
|
||||||
|
spindexPos = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
} else if (shootAll) {
|
||||||
|
|
||||||
|
TELE.addData("100% works", shootOrder);
|
||||||
|
|
||||||
|
intake = false;
|
||||||
|
reject = false;
|
||||||
|
|
||||||
|
if (!shootOrder.isEmpty() && (getRuntime() - shootStamp < 12)) {
|
||||||
|
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
||||||
|
boolean shootingDone = false;
|
||||||
|
|
||||||
|
if (!outtake1) {
|
||||||
|
outtake1 = (servo.spinEqual(spindexer_outtakeBall1));
|
||||||
|
}
|
||||||
|
if (!outtake2) {
|
||||||
|
outtake2 = (servo.spinEqual(spindexer_outtakeBall2));
|
||||||
|
}
|
||||||
|
if (!outtake3) {
|
||||||
|
outtake3 = (servo.spinEqual(spindexer_outtakeBall3));
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (currentSlot) {
|
||||||
|
case 1:
|
||||||
|
shootA = shootTeleop(spindexer_outtakeBall1, outtake1, shootStamp2);
|
||||||
|
TELE.addData("shootA", shootA);
|
||||||
|
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootA;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
shootB = shootTeleop(spindexer_outtakeBall2, outtake2, shootStamp2);
|
||||||
|
TELE.addData("shootB", shootB);
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootB;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
shootC = shootTeleop(spindexer_outtakeBall3, outtake3, shootStamp2);
|
||||||
|
TELE.addData("shootC", shootC);
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootC;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Remove from the list only if shooting is complete
|
||||||
|
if (shootingDone) {
|
||||||
|
shootOrder.remove(0);
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// Finished shooting all balls
|
||||||
|
spindexPos = spindexer_intakePos1;
|
||||||
|
shootA = true;
|
||||||
|
shootB = true;
|
||||||
|
shootC = true;
|
||||||
|
reject = false;
|
||||||
|
intake = true;
|
||||||
|
shootAll = false;
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.squareWasPressed()) {
|
||||||
|
square = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.circleWasPressed()) {
|
||||||
|
circle = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.triangleWasPressed()) {
|
||||||
|
triangle = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (square || circle || triangle) {
|
||||||
|
|
||||||
|
// Count green balls
|
||||||
|
int greenCount = 0;
|
||||||
|
if (green1) greenCount++;
|
||||||
|
if (green2) greenCount++;
|
||||||
|
if (green3) greenCount++;
|
||||||
|
|
||||||
|
// Determine the odd ball color
|
||||||
|
oddBallColor = greenCount < 2; // true = green, false = purple
|
||||||
|
|
||||||
|
shootOrder.clear();
|
||||||
|
|
||||||
|
// Determine shooting order based on button pressed
|
||||||
|
// square = odd ball first, triangle = odd ball second, circle = odd ball third
|
||||||
|
if (square) {
|
||||||
|
// Odd ball first
|
||||||
|
addOddThenRest(shootOrder, oddBallColor);
|
||||||
|
|
||||||
|
} else if (triangle) {
|
||||||
|
// Odd ball second
|
||||||
|
addOddInMiddle(shootOrder, oddBallColor);
|
||||||
|
} else if (circle) {
|
||||||
|
// Odd ball last
|
||||||
|
addOddLast(shootOrder, oddBallColor);
|
||||||
|
}
|
||||||
|
|
||||||
|
circle = false;
|
||||||
|
square = false;
|
||||||
|
triangle = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Right bumper shoots all balls fastest, ignoring colors
|
||||||
|
if (gamepad2.rightBumperWasPressed()) {
|
||||||
|
shootOrder.clear();
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
// Fastest order (example: slot 3 → 2 → 1)
|
||||||
|
|
||||||
|
if (ballIn(3)) {
|
||||||
|
shootOrder.add(3);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ballIn(2)) {
|
||||||
|
shootOrder.add(2);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ballIn(1)) {
|
||||||
|
shootOrder.add(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(3)) {
|
||||||
|
|
||||||
|
shootOrder.add(3);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(2)) {
|
||||||
|
|
||||||
|
shootOrder.add(2);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(1)) {
|
||||||
|
|
||||||
|
shootOrder.add(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
shootAll = true;
|
||||||
|
shootPos = drive.localizer.getPose();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// // Right bumper shoots all balls fastest, ignoring colors
|
||||||
|
// if (gamepad2.leftBumperWasPressed()) {
|
||||||
|
// shootOrder.clear();
|
||||||
|
// shootStamp = getRuntime();
|
||||||
|
//
|
||||||
|
// outtake1 = false;
|
||||||
|
// outtake2 = false;
|
||||||
|
// outtake3 = false;
|
||||||
|
//
|
||||||
|
// // Fastest order (example: slot 3 → 2 → 1)
|
||||||
|
//
|
||||||
|
// if (ballIn(3)) {
|
||||||
|
// shootOrder.add(3);
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// if (ballIn(2)) {
|
||||||
|
// shootOrder.add(2);
|
||||||
|
// }
|
||||||
|
// if (ballIn(1)) {
|
||||||
|
// shootOrder.add(1);
|
||||||
|
// }
|
||||||
|
// shootAll = true;
|
||||||
|
// shootPos = drive.localizer.getPose();
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
if (gamepad2.crossWasPressed()) {
|
||||||
|
emergency = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.leftBumperWasPressed()) {
|
||||||
|
emergency = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
//MISC:
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.clearBulkCache();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
||||||
|
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
||||||
|
TELE.addData("Spin3Green", green3 + ": " + ballIn(3));
|
||||||
|
|
||||||
|
TELE.addData("pose", drive.localizer.getPose());
|
||||||
|
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
||||||
|
TELE.addData("distanceToGoal", distanceToGoal);
|
||||||
|
TELE.addData("hood", robot.hood.getPosition());
|
||||||
|
TELE.addData("targetVel", vel);
|
||||||
|
|
||||||
|
TELE.addData("shootOrder", shootOrder);
|
||||||
|
TELE.addData("oddColor", oddBallColor);
|
||||||
|
|
||||||
|
aprilTagWebcam.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Helper method
|
||||||
|
private boolean checkGreen(List<Boolean> s, List<Double> sT) {
|
||||||
|
if (s.isEmpty()) return false;
|
||||||
|
|
||||||
|
double lastTime = sT.get(sT.size() - 1);
|
||||||
|
int countTrue = 0;
|
||||||
|
int countWindow = 0;
|
||||||
|
|
||||||
|
for (int i = 0; i < s.size(); i++) {
|
||||||
|
if (lastTime - sT.get(i) <= 3.0) { // element is within 2s of last
|
||||||
|
countWindow++;
|
||||||
|
if (s.get(i)) {
|
||||||
|
countTrue++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (countWindow == 0) return false; // avoid divide by zero
|
||||||
|
return countTrue > countWindow / 2.0; // more than 50% true
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
||||||
|
// Set spin positions
|
||||||
|
spindexPos = spindexer;
|
||||||
|
|
||||||
|
// Check if spindexer has reached the target position
|
||||||
|
if (spinOk || getRuntime() - stamp > 1.5) {
|
||||||
|
if (tickerA == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
tickerA++;
|
||||||
|
TELE.addLine("tickerSet");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
transferIn = true;
|
||||||
|
TELE.addLine("transferring");
|
||||||
|
|
||||||
|
return true; // still in progress
|
||||||
|
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
transferIn = false; // reset for next shot
|
||||||
|
tickerA = 1; // reset ticker
|
||||||
|
transferStamp = 0.0;
|
||||||
|
|
||||||
|
TELE.addLine("shotFinished");
|
||||||
|
|
||||||
|
return false; // finished shooting
|
||||||
|
} else {
|
||||||
|
TELE.addLine("sIP");
|
||||||
|
return true; // still in progress
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
tickerA = 1;
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
transferIn = false;
|
||||||
|
return true; // still moving spin
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public double hoodAnglePrediction(double x) {
|
||||||
|
if (x < 34) {
|
||||||
|
double L = 1.04471;
|
||||||
|
double U = 0.711929;
|
||||||
|
double Q = 120.02263;
|
||||||
|
double B = 0.780982;
|
||||||
|
double M = 20.61191;
|
||||||
|
double v = 10.40506;
|
||||||
|
|
||||||
|
double inner = 1 + Q * Math.exp(-B * (x - M));
|
||||||
|
return L + (U - L) / Math.pow(inner, 1.0 / v);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// x >= 34
|
||||||
|
return 1.94372 * Math.exp(-0.0528731 * x) + 0.39;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddThenRest(List<Integer> order, boolean oddColor) {
|
||||||
|
// Odd ball first
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||||
|
TELE.addData("1", shootOrder);
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||||
|
TELE.addData("works", shootOrder);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddInMiddle(List<Integer> order, boolean oddColor) {
|
||||||
|
|
||||||
|
boolean[] used = new boolean[4]; // index 1..3
|
||||||
|
|
||||||
|
// 1) Add a NON-odd ball first
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (getBallColor(i) != oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 2) Add the odd ball second
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (!used[i] && getBallColor(i) == oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 3) Add the remaining non-odd ball third
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (!used[i] && getBallColor(i) != oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("works", order);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddLast(List<Integer> order, boolean oddColor) {
|
||||||
|
// Odd ball last
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||||
|
TELE.addData("1", shootOrder);
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||||
|
TELE.addData("works", shootOrder);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns color of ball in slot i (1-based)
|
||||||
|
boolean getBallColor(int slot) {
|
||||||
|
switch (slot) {
|
||||||
|
case 1:
|
||||||
|
return green1;
|
||||||
|
case 2:
|
||||||
|
return green2;
|
||||||
|
case 3:
|
||||||
|
return green3;
|
||||||
|
}
|
||||||
|
return false; // default
|
||||||
|
}
|
||||||
|
|
||||||
|
boolean ballIn(int slot) {
|
||||||
|
switch (slot) {
|
||||||
|
case 1:
|
||||||
|
|
||||||
|
if (!s1T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s1T.get(s1T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
case 2:
|
||||||
|
|
||||||
|
if (!s2T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s2T.get(s2T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
case 3:
|
||||||
|
|
||||||
|
if (!s3T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s3T.get(s3T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return true; // default
|
||||||
|
}
|
||||||
|
}
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,793 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.ToggleButtonReader;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Drivetrain;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Intake;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Spindexer;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Transfer;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
@Disabled
|
||||||
|
public class old extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
Drivetrain drivetrain;
|
||||||
|
|
||||||
|
Intake intake;
|
||||||
|
|
||||||
|
Spindexer spindexer;
|
||||||
|
|
||||||
|
Transfer transfer;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
GamepadEx g1;
|
||||||
|
|
||||||
|
GamepadEx g2;
|
||||||
|
|
||||||
|
public static double defaultSpeed = 1;
|
||||||
|
|
||||||
|
public static double slowMoSpeed = 0.4;
|
||||||
|
|
||||||
|
public static double power = 0.0;
|
||||||
|
|
||||||
|
public static double pos = hoodDefault;
|
||||||
|
|
||||||
|
public boolean all = false;
|
||||||
|
|
||||||
|
public int ticker = 0;
|
||||||
|
|
||||||
|
ToggleButtonReader g1RightBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Circle;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Square;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Triangle;
|
||||||
|
|
||||||
|
ToggleButtonReader g2RightBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g1LeftBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2LeftBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadUp;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadDown;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadRight;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadLeft;
|
||||||
|
|
||||||
|
public boolean leftBumper = false;
|
||||||
|
public double g1RightBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public double g1LeftBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public double g2LeftBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public static int spindexerPos = 0;
|
||||||
|
|
||||||
|
public boolean green = false;
|
||||||
|
|
||||||
|
Shooter shooter;
|
||||||
|
|
||||||
|
public boolean scoreAll = false;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
public boolean autotrack = false;
|
||||||
|
|
||||||
|
public int last = 0;
|
||||||
|
public int second = 0;
|
||||||
|
|
||||||
|
public double offset = 0.0;
|
||||||
|
|
||||||
|
public static double rIn = 0.59;
|
||||||
|
|
||||||
|
public static double rOut = 0;
|
||||||
|
|
||||||
|
public boolean notShooting = true;
|
||||||
|
|
||||||
|
public boolean circle = false;
|
||||||
|
|
||||||
|
public boolean square = false;
|
||||||
|
|
||||||
|
public boolean tri = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
FtcDashboard.getInstance().getTelemetry(),
|
||||||
|
telemetry
|
||||||
|
);
|
||||||
|
|
||||||
|
g1 = new GamepadEx(gamepad1);
|
||||||
|
|
||||||
|
g1RightBumper = new ToggleButtonReader(
|
||||||
|
g1, GamepadKeys.Button.RIGHT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2 = new GamepadEx(gamepad2);
|
||||||
|
|
||||||
|
g1LeftBumper = new ToggleButtonReader(
|
||||||
|
g1, GamepadKeys.Button.LEFT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Circle = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.B
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Triangle = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.Y
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Square = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.X
|
||||||
|
);
|
||||||
|
|
||||||
|
g2RightBumper = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.RIGHT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2LeftBumper = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.LEFT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadUp = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_UP
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadDown = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_DOWN
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadLeft = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_LEFT
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadRight = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_RIGHT
|
||||||
|
);
|
||||||
|
|
||||||
|
drivetrain = new Drivetrain(robot, TELE, g1);
|
||||||
|
|
||||||
|
drivetrain.setMode("Default");
|
||||||
|
|
||||||
|
drivetrain.setDefaultSpeed(defaultSpeed);
|
||||||
|
|
||||||
|
drivetrain.setSlowSpeed(slowMoSpeed);
|
||||||
|
|
||||||
|
intake = new Intake(robot);
|
||||||
|
|
||||||
|
transfer = new Transfer(robot);
|
||||||
|
|
||||||
|
spindexer = new Spindexer(robot, TELE);
|
||||||
|
|
||||||
|
spindexer.setTelemetryOn(true);
|
||||||
|
|
||||||
|
shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
shooter.setShooterMode("MANUAL");
|
||||||
|
|
||||||
|
robot.rejecter.setPosition(rIn);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
TELE.addData("pose", drive.localizer.getPose());
|
||||||
|
|
||||||
|
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
||||||
|
|
||||||
|
TELE.addData("off", offset);
|
||||||
|
|
||||||
|
robot.hood.setPosition(pos);
|
||||||
|
|
||||||
|
g1LeftBumper.readValue();
|
||||||
|
|
||||||
|
if (g1LeftBumper.wasJustPressed()) {
|
||||||
|
g2LeftBumperStamp = getRuntime();
|
||||||
|
|
||||||
|
spindexer.intakeShake(getRuntime());
|
||||||
|
|
||||||
|
leftBumper = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (leftBumper) {
|
||||||
|
double time = getRuntime() - g2LeftBumperStamp;
|
||||||
|
|
||||||
|
if (time < 1.0) {
|
||||||
|
robot.rejecter.setPosition(rOut);
|
||||||
|
} else {
|
||||||
|
robot.rejecter.setPosition(rIn);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
intake();
|
||||||
|
|
||||||
|
drivetrain.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
g2RightBumper.readValue();
|
||||||
|
|
||||||
|
g2LeftBumper.readValue();
|
||||||
|
|
||||||
|
g2DpadDown.readValue();
|
||||||
|
|
||||||
|
g2DpadUp.readValue();
|
||||||
|
|
||||||
|
if (!scoreAll) {
|
||||||
|
spindexer.checkForBalls();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadUp.wasJustPressed()) {
|
||||||
|
pos -= 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadDown.wasJustPressed()) {
|
||||||
|
pos += 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
g2DpadLeft.readValue();
|
||||||
|
|
||||||
|
g2DpadRight.readValue();
|
||||||
|
|
||||||
|
if (g2DpadLeft.wasJustPressed()) {
|
||||||
|
offset -= 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadRight.wasJustPressed()) {
|
||||||
|
offset += 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("hood", pos);
|
||||||
|
|
||||||
|
if (Math.abs(gamepad2.right_stick_x) < 0.1 && autotrack) {
|
||||||
|
|
||||||
|
shooter.trackGoal(drive.localizer.getPose(), new Pose2d(-10, 0, 0), offset);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
autotrack = false;
|
||||||
|
|
||||||
|
shooter.moveTurret(0.3 + offset);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.right_stick_button) {
|
||||||
|
autotrack = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2RightBumper.wasJustPressed()) {
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
transfer.transferIn();
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
notShooting = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2RightBumper.wasJustReleased()) {
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
transfer.transferOut();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_y > 0.5) {
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
} else if (gamepad2.left_stick_y < -0.5) {
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2LeftBumper.wasJustPressed()) {
|
||||||
|
g2LeftBumperStamp = getRuntime();
|
||||||
|
notShooting = false;
|
||||||
|
scoreAll = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (scoreAll) {
|
||||||
|
double time = getRuntime() - g2LeftBumperStamp;
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
TELE.addData("greenImportant", green);
|
||||||
|
|
||||||
|
TELE.addData("last", last);
|
||||||
|
TELE.addData("2ndLast", second);
|
||||||
|
|
||||||
|
int numGreen = spindexer.greens();
|
||||||
|
|
||||||
|
if (square) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else if (tri) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else if (circle) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
} else {
|
||||||
|
all = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake3();
|
||||||
|
last = 3;
|
||||||
|
second = 3;
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
last = 2;
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake1();
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intake() {
|
||||||
|
|
||||||
|
g1RightBumper.readValue();
|
||||||
|
|
||||||
|
g2Circle.readValue();
|
||||||
|
|
||||||
|
g2Square.readValue();
|
||||||
|
|
||||||
|
g2Triangle.readValue();
|
||||||
|
|
||||||
|
if (g1RightBumper.wasJustPressed()) {
|
||||||
|
|
||||||
|
notShooting = true;
|
||||||
|
|
||||||
|
if (getRuntime() - g1RightBumperStamp < 0.3) {
|
||||||
|
intake.reverse();
|
||||||
|
} else {
|
||||||
|
intake.toggle();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake.getIntakeState() == 1) {
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.intake();
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
g1RightBumperStamp = getRuntime();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake.getIntakeState() == 1 && notShooting) {
|
||||||
|
|
||||||
|
spindexer.intakeShake(getRuntime());
|
||||||
|
|
||||||
|
} else {
|
||||||
|
if (g2Circle.wasJustPressed()) {
|
||||||
|
circle = true;
|
||||||
|
tri = false;
|
||||||
|
square = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2Triangle.wasJustPressed()) {
|
||||||
|
circle = false;
|
||||||
|
tri = true;
|
||||||
|
square = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2Square.wasJustPressed()) {
|
||||||
|
circle = false;
|
||||||
|
tri = false;
|
||||||
|
square = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.x) {
|
||||||
|
circle = false;
|
||||||
|
tri = false;
|
||||||
|
square = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
intake.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
@@ -0,0 +1,144 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ActiveColorSensorTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException{
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
int b1Purple = 1;
|
||||||
|
int b1Total = 1;
|
||||||
|
int b2Purple = 1;
|
||||||
|
int b2Total = 1;
|
||||||
|
int b3Purple = 1;
|
||||||
|
int b3Total = 1;
|
||||||
|
|
||||||
|
double totalStamp1 = 0.0;
|
||||||
|
double purpleStamp1 = 0.0;
|
||||||
|
double totalStamp2 = 0.0;
|
||||||
|
double purpleStamp2 = 0.0;
|
||||||
|
double totalStamp3 = 0.0;
|
||||||
|
double purpleStamp3 = 0.0;
|
||||||
|
|
||||||
|
String b1 = "none";
|
||||||
|
String b2 = "none";
|
||||||
|
String b3 = "none";
|
||||||
|
|
||||||
|
double position = 0.0;
|
||||||
|
|
||||||
|
double stamp = getRuntime();
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()){
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) >0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.015;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.015;
|
||||||
|
}
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1-position);
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
// Reset the counters after 1 second of not reading a ball.
|
||||||
|
final double ColorCounterResetDelay = 1.0;
|
||||||
|
// Number of times the loop needs to run before deciding on a color.
|
||||||
|
final int ColorCounterTotalMinCount = 20;
|
||||||
|
// If the color sensor reads a color this percentage of time
|
||||||
|
// out of the total, declare the color.
|
||||||
|
// Usage: (Color Count)/(Total Count) > ColorCounterThreshold
|
||||||
|
final double ColorCounterThreshold = 0.65;
|
||||||
|
|
||||||
|
if (robot.pin1.getState()){
|
||||||
|
if (robot.pin0.getState()){
|
||||||
|
b1Purple ++;
|
||||||
|
}
|
||||||
|
b1Total++;
|
||||||
|
totalStamp1 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp1 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b1 = "none";
|
||||||
|
b1Total = 1;
|
||||||
|
b1Purple = 1;
|
||||||
|
}else if ((b1Total > ColorCounterTotalMinCount) && ((double) b1Purple / b1Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b1 = "Purple";
|
||||||
|
}else if (b1Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b1 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
if (robot.pin3.getState()){
|
||||||
|
if (robot.pin2.getState()){
|
||||||
|
b2Purple ++;
|
||||||
|
}
|
||||||
|
b2Total++;
|
||||||
|
totalStamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp2 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b2 = "none";
|
||||||
|
b2Total = 1;
|
||||||
|
b2Purple = 1;
|
||||||
|
}else if ((b2Total > ColorCounterTotalMinCount) && ((double) b2Purple / b2Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b2 = "Purple";
|
||||||
|
}else if (b2Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b2 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
if (robot.pin5.getState()){
|
||||||
|
if (robot.pin4.getState()){
|
||||||
|
b3Purple ++;
|
||||||
|
}
|
||||||
|
b3Total++;
|
||||||
|
totalStamp3 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp3 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b3 = "none";
|
||||||
|
b3Total = 1;
|
||||||
|
b3Purple = 1;
|
||||||
|
}else if ((b3Total > ColorCounterTotalMinCount) && ((double) b3Purple / b3Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b3 = "Purple";
|
||||||
|
}else if (b3Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b3 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Green1:", robot.pin1.getState());
|
||||||
|
TELE.addData("Purple1:", robot.pin0.getState());
|
||||||
|
TELE.addData("Green2:", robot.pin3.getState());
|
||||||
|
TELE.addData("Purple2:", robot.pin2.getState());
|
||||||
|
TELE.addData("Green3:", robot.pin5.getState());
|
||||||
|
TELE.addData("Purple3:", robot.pin4.getState());
|
||||||
|
TELE.addData("1", b1);
|
||||||
|
TELE.addData("2",b2);
|
||||||
|
TELE.addData("3",b3);
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,37 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class AprilTagWebcamExample extends OpMode {
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
AprilTagWebcam aprilTagWebcam = new AprilTagWebcam();
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void init() {
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void loop() {
|
||||||
|
|
||||||
|
aprilTagWebcam.update();
|
||||||
|
aprilTagWebcam.displayAllTelemetry();
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,63 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ColorSensorTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
// ----- COLOR 1 -----
|
||||||
|
double green1 = robot.color1.getNormalizedColors().green;
|
||||||
|
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||||
|
double red1 = robot.color1.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||||
|
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
// ----- COLOR 2 -----
|
||||||
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
double red2 = robot.color2.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||||
|
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
// ----- COLOR 3 -----
|
||||||
|
double green3 = robot.color3.getNormalizedColors().green;
|
||||||
|
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||||
|
double red3 = robot.color3.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||||
|
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
@@ -1,61 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
|
||||||
|
|
||||||
@Disabled
|
|
||||||
public class ColorSensorTester extends LinearOpMode {
|
|
||||||
|
|
||||||
|
|
||||||
public static String portAName = "pin0";
|
|
||||||
|
|
||||||
public static String portBName = "pin1";
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
|
|
||||||
DigitalChannel pinA = hardwareMap.digitalChannel.get(portAName);
|
|
||||||
DigitalChannel pinB = hardwareMap.digitalChannel.get(portBName);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
|
||||||
telemetry,
|
|
||||||
FtcDashboard.getInstance().getTelemetry()
|
|
||||||
);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if(isStopRequested()) return;
|
|
||||||
|
|
||||||
while(opModeIsActive()){
|
|
||||||
|
|
||||||
TELE.addData("pinA", pinA.getState());
|
|
||||||
TELE.addData("pinB", pinB.getState());
|
|
||||||
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,55 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class ColorTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while(opModeIsActive()){
|
||||||
|
double green1 = robot.color1.getNormalizedColors().green;
|
||||||
|
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||||
|
double red1 = robot.color1.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||||
|
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
// ----- COLOR 2 -----
|
||||||
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
double red2 = robot.color2.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||||
|
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
// ----- COLOR 3 -----
|
||||||
|
double green3 = robot.color3.getNormalizedColors().green;
|
||||||
|
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||||
|
double red3 = robot.color3.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||||
|
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,223 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class IntakeTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
Servos servo;
|
||||||
|
public boolean green1 = false;
|
||||||
|
public boolean green2 = false;
|
||||||
|
public boolean green3 = false;
|
||||||
|
List<Double> s1G = new ArrayList<>();
|
||||||
|
List<Double> s2G = new ArrayList<>();
|
||||||
|
List<Double> s3G = new ArrayList<>();
|
||||||
|
List<Double> s1T = new ArrayList<>();
|
||||||
|
List<Double> s2T = new ArrayList<>();
|
||||||
|
List<Double> s3T = new ArrayList<>();
|
||||||
|
List<Boolean> s1 = new ArrayList<>();
|
||||||
|
List<Boolean> s2 = new ArrayList<>();
|
||||||
|
List<Boolean> s3 = new ArrayList<>();
|
||||||
|
public static int mode = 0; // 0 for teleop, 1 for auto
|
||||||
|
public static double manualPow = 0.15;
|
||||||
|
double stamp = 0;
|
||||||
|
int ticker = 0;
|
||||||
|
boolean steadySpin = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
boolean intake = true;
|
||||||
|
double spindexerPos = spindexer_intakePos1;
|
||||||
|
boolean wasMoving = false;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
boolean reverse = false;
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||||
|
}
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
if (mode == 0) {
|
||||||
|
if (gamepad1.right_bumper) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 16 == 0){
|
||||||
|
currentPos = servo.getSpinPos();
|
||||||
|
if (Math.abs(currentPos - initPos) == 0.0){
|
||||||
|
reverse = !reverse;
|
||||||
|
}
|
||||||
|
initPos = currentPos;
|
||||||
|
}
|
||||||
|
if (reverse){
|
||||||
|
robot.spin1.setPower(manualPow);
|
||||||
|
robot.spin2.setPower(-manualPow);
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(-manualPow);
|
||||||
|
robot.spin2.setPower(manualPow);
|
||||||
|
}
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
stamp = getRuntime();
|
||||||
|
TELE.addData("Reverse?", reverse);
|
||||||
|
TELE.update();
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 1) {
|
||||||
|
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
}
|
||||||
|
} else if (mode == 1) {
|
||||||
|
|
||||||
|
if (gamepad1.right_bumper && intake){
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
} else if (gamepad1.left_bumper){
|
||||||
|
robot.intake.setPower(-1);
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
colorDetect();
|
||||||
|
spindexer();
|
||||||
|
|
||||||
|
if (ballIn(1) && steadySpin && intake && getRuntime() - stamp > 0.5){
|
||||||
|
if (!ballIn(2)){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
spindexerPos = spindexer_intakePos2;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
spindexerPos = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
spindexerPos = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
} else if (!ballIn(3)){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
spindexerPos = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
spindexerPos = spindexer_intakePos1;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
spindexerPos = spindexer_intakePos2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (mode == 2){ // switch to this mode before switching modes or to reset balls
|
||||||
|
powPID = 0;
|
||||||
|
spindexerPos = spindexer_intakePos1;
|
||||||
|
stamp = getRuntime();
|
||||||
|
ticker = 0;
|
||||||
|
spindexer();
|
||||||
|
intake = true;
|
||||||
|
}
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.clearBulkCache();
|
||||||
|
}
|
||||||
|
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
||||||
|
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
||||||
|
double rx = gamepad1.left_stick_x;
|
||||||
|
|
||||||
|
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||||
|
double frontLeftPower = (y + x + rx) / denominator;
|
||||||
|
double backLeftPower = (y - x + rx) / denominator;
|
||||||
|
double frontRightPower = (y - x - rx) / denominator;
|
||||||
|
double backRightPower = (y + x - rx) / denominator;
|
||||||
|
|
||||||
|
robot.frontLeft.setPower(frontLeftPower);
|
||||||
|
robot.backLeft.setPower(backLeftPower);
|
||||||
|
robot.frontRight.setPower(frontRightPower);
|
||||||
|
robot.backRight.setPower(backRightPower);
|
||||||
|
|
||||||
|
TELE.addData("Manual Power", manualPow);
|
||||||
|
TELE.addData("PID Power", powPID);
|
||||||
|
TELE.addData("B1", ballIn(1));
|
||||||
|
TELE.addData("B2", ballIn(2));
|
||||||
|
TELE.addData("B3", ballIn(3));
|
||||||
|
TELE.addData("Spindex Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void colorDetect() {
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
TELE.addData("Color 1 Distance", s1D);
|
||||||
|
TELE.addData("Color 2 Distance", s2D);
|
||||||
|
TELE.addData("Color 3 Distance", s3D);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
s1T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
s2T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
s3T.add(getRuntime());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void spindexer() {
|
||||||
|
boolean atTarget = servo.spinEqual(spindexerPos);
|
||||||
|
|
||||||
|
if (!atTarget) {
|
||||||
|
powPID = servo.setSpinPos(spindexerPos);
|
||||||
|
robot.spin1.setPower(powPID);
|
||||||
|
robot.spin2.setPower(-powPID);
|
||||||
|
|
||||||
|
steadySpin = false;
|
||||||
|
wasMoving = true; // remember we were moving
|
||||||
|
stamp = getRuntime();
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
steadySpin = true;
|
||||||
|
wasMoving = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
boolean ballIn(int slot) {
|
||||||
|
List<Double> times;
|
||||||
|
|
||||||
|
if (slot == 1) {times = s1T;}
|
||||||
|
else if (slot == 2) {times = s2T;}
|
||||||
|
else if (slot == 3) {times = s3T;}
|
||||||
|
else return false;
|
||||||
|
|
||||||
|
if (!times.isEmpty()){
|
||||||
|
return times.get(times.size() - 1) > getRuntime() - 2;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -3,55 +3,75 @@ package org.firstinspires.ftc.teamcode.tests;
|
|||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import java.util.List;
|
||||||
import org.firstinspires.ftc.teamcode.utils.subsystems.Limelight;
|
|
||||||
|
|
||||||
|
|
||||||
@Autonomous
|
|
||||||
@Config
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
//TODO: fix to get the apriltag that it is reading
|
||||||
public class LimelightTest extends LinearOpMode {
|
public class LimelightTest extends LinearOpMode {
|
||||||
|
|
||||||
public static String MODE = "AT";
|
|
||||||
public static int pipe = 1;
|
|
||||||
|
|
||||||
|
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
|
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
||||||
Robot robot;
|
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
|
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
limelight.pipelineSwitch(pipeline);
|
||||||
Limelight limelight = new Limelight(robot, TELE);
|
|
||||||
|
|
||||||
limelight.setMode(MODE);
|
|
||||||
|
|
||||||
limelight.setTelemetryOn(true);
|
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
limelight.start();
|
||||||
|
while (opModeIsActive()){
|
||||||
|
if (mode == 0){
|
||||||
|
limelight.pipelineSwitch(pipeline);
|
||||||
|
LLResult result = limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
TELE.addData("tx", result.getTx());
|
||||||
|
TELE.addData("ty", result.getTy());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else if (mode == 1){
|
||||||
|
limelight.pipelineSwitch(1);
|
||||||
|
LLResult result = limelight.getLatestResult();
|
||||||
|
if (result != null && result.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
int id = fiducial.getFiducialId();
|
||||||
|
TELE.addData("ID", id);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
if(isStopRequested()) return;
|
}
|
||||||
|
} else if (mode == 2){
|
||||||
while(opModeIsActive()){
|
limelight.pipelineSwitch(4);
|
||||||
|
LLResult result = limelight.getLatestResult();
|
||||||
limelight.setPipeline(pipe);
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
limelight.setMode(MODE);
|
TELE.addData("tx", result.getTx());
|
||||||
|
TELE.addData("ty", result.getTy());
|
||||||
limelight.update();
|
TELE.update();
|
||||||
|
}
|
||||||
TELE.update();
|
}
|
||||||
|
} else if (mode == 3){
|
||||||
|
limelight.pipelineSwitch(5);
|
||||||
|
LLResult result = limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
TELE.addData("tx", result.getTx());
|
||||||
|
TELE.addData("ty", result.getTy());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
limelight.pipelineSwitch(0);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,45 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class MotorDirectionDebugger extends LinearOpMode {
|
||||||
|
|
||||||
|
public static double flPower = 0.0;
|
||||||
|
|
||||||
|
public static double frPower = 0.0;
|
||||||
|
|
||||||
|
public static double blPower = 0.0;
|
||||||
|
public static double brPower = 0.0;
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if(isStopRequested()) return;
|
||||||
|
|
||||||
|
while(opModeIsActive()){
|
||||||
|
|
||||||
|
robot.frontLeft.setPower(flPower);
|
||||||
|
robot.frontRight.setPower(frPower);
|
||||||
|
robot.backRight.setPower(brPower);
|
||||||
|
robot.backLeft.setPower(blPower);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,65 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class PIDServoTest extends LinearOpMode {
|
||||||
|
|
||||||
|
public static double p = 2, i = 0, d = 0, f = 0;
|
||||||
|
|
||||||
|
public static double target = 0.5;
|
||||||
|
|
||||||
|
public static int mode = 0; //0 is for turret, 1 is for spindexer
|
||||||
|
|
||||||
|
public static double scalar = 1.01;
|
||||||
|
public static double restPos = 0.0;
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
double pos = 0.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
PIDFController controller = new PIDFController(p, i, d, f);
|
||||||
|
|
||||||
|
controller.setTolerance(0.001);
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
controller.setPIDF(p, i, d, f);
|
||||||
|
if (mode == 1) {
|
||||||
|
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
||||||
|
|
||||||
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
|
robot.spin1.setPower(pid);
|
||||||
|
robot.spin2.setPower(-pid);
|
||||||
|
}
|
||||||
|
|
||||||
|
telemetry.addData("pos", pos);
|
||||||
|
telemetry.addData("Turret Voltage", robot.turr1Pos.getCurrentPosition());
|
||||||
|
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
||||||
|
telemetry.addData("target", target);
|
||||||
|
telemetry.addData("Mode", mode);
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,85 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class ShooterTest extends LinearOpMode {
|
||||||
|
|
||||||
|
public static int mode = 0;
|
||||||
|
public static double parameter = 0.0;
|
||||||
|
// --- CONSTANTS YOU TUNE ---
|
||||||
|
|
||||||
|
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||||
|
public static double Velocity = 0.0;
|
||||||
|
public static double P = 40.0;
|
||||||
|
public static double I = 0.3;
|
||||||
|
public static double D = 7.0;
|
||||||
|
public static double F = 10.0;
|
||||||
|
public static double transferPower = 1.0;
|
||||||
|
public static double hoodPos = 0.501;
|
||||||
|
public static double turretPos = 0.501;
|
||||||
|
public static boolean shoot = false;
|
||||||
|
Robot robot;
|
||||||
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
if (mode == 0) {
|
||||||
|
rightShooter.setPower(parameter);
|
||||||
|
leftShooter.setPower(parameter);
|
||||||
|
} else if (mode == 1) {
|
||||||
|
flywheel.setPIDF(P,I,D,F);
|
||||||
|
flywheel.manageFlywheel((int) Velocity);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hoodPos != 0.501) {
|
||||||
|
robot.hood.setPosition(hoodPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
robot.transfer.setPower(transferPower);
|
||||||
|
if (shoot) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
}
|
||||||
|
TELE.addData("Velocity", flywheel.getVelo());
|
||||||
|
TELE.addData("Velocity 1", flywheel.getVelo1());
|
||||||
|
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||||
|
TELE.addData("Power", robot.shooter1.getPower());
|
||||||
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
|
TELE.addData("Position", robot.shooter1.getCurrentPosition());
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,210 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ShooterTest extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
public static double pow = 0.0;
|
||||||
|
public static double vel = 0.0;
|
||||||
|
public static double ecpr = 1024.0; // CPR of the encoder
|
||||||
|
public static double hoodPos = 0.5;
|
||||||
|
public static double turretPos = 0.9;
|
||||||
|
|
||||||
|
public static String flyMode = "VEL";
|
||||||
|
|
||||||
|
public static boolean AutoTrack = false;
|
||||||
|
|
||||||
|
double initPos = 0.0;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
double velo1 = 0.0;
|
||||||
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
|
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
|
||||||
|
double initPos1 = 0.0;
|
||||||
|
|
||||||
|
double powPID = 0.0;
|
||||||
|
|
||||||
|
public static int maxVel = 4500;
|
||||||
|
|
||||||
|
public static boolean shoot = false;
|
||||||
|
|
||||||
|
public static int spindexPos = 1;
|
||||||
|
|
||||||
|
public static boolean intake = true;
|
||||||
|
|
||||||
|
public static int tolerance = 50;
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
public static double distance = 50;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
Shooter shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
robot.shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
robot.shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
shooter.setTelemetryOn(true);
|
||||||
|
|
||||||
|
shooter.setShooterMode(flyMode);
|
||||||
|
|
||||||
|
initPos = shooter.getECPRPosition();
|
||||||
|
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (AutoTrack){
|
||||||
|
hoodPos = hoodAnglePrediction(distance);
|
||||||
|
vel = velPrediction(distance);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.setShooterMode(flyMode);
|
||||||
|
|
||||||
|
shooter.setManualPower(pow);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodPos);
|
||||||
|
robot.turr1.setPosition(turretPos);
|
||||||
|
robot.turr2.setPosition(1 - turretPos);
|
||||||
|
if (intake) {
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
robot.intake.setPower(0.75);
|
||||||
|
robot.spin1.setPosition(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_intakePos1);
|
||||||
|
} else {
|
||||||
|
robot.transfer.setPower(.75 + (powPID/4));
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
if (spindexPos == 1) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall1);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall1);
|
||||||
|
} else if (spindexPos == 2) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall2);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall2);
|
||||||
|
} else if (spindexPos == 3) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall3);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall3);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
double penguin = 0;
|
||||||
|
if (ticker % 8 ==0){
|
||||||
|
penguin = shooter.getECPRPosition();
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo1 = -60 * ((penguin - initPos1) / (stamp - stamp1));
|
||||||
|
initPos1 = penguin;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
velo = velo1;
|
||||||
|
|
||||||
|
double feed = vel / maxVel; // Example: vel=2500 → feed=0.5
|
||||||
|
|
||||||
|
if (vel > 500){
|
||||||
|
feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
}
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo1;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
|
||||||
|
if (vel - velo > 1000){
|
||||||
|
powPID = 1;
|
||||||
|
} else if (velo - vel > 1000){
|
||||||
|
powPID = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.setVelocity(powPID);
|
||||||
|
|
||||||
|
if (shoot) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
TELE.addData("Revolutions", shooter.getECPRPosition());
|
||||||
|
TELE.addData("hoodPos", shooter.gethoodPosition());
|
||||||
|
TELE.addData("turretPos", shooter.getTurretPosition());
|
||||||
|
TELE.addData("Power Fly 1", robot.shooter1.getPower());
|
||||||
|
TELE.addData("Power Fly 2", robot.shooter2.getPower());
|
||||||
|
TELE.addData("powPID", shooter.getpowPID());
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public double hoodAnglePrediction(double distance) {
|
||||||
|
double L = 0.298317;
|
||||||
|
double A = 1.02124;
|
||||||
|
double k = 0.0157892;
|
||||||
|
double n = 3.39375;
|
||||||
|
|
||||||
|
double dist = Math.sqrt(distance*distance+24*24);
|
||||||
|
|
||||||
|
return L + A * Math.exp(-Math.pow(k * dist, n));
|
||||||
|
}
|
||||||
|
public static double velPrediction(double distance) {
|
||||||
|
|
||||||
|
double x = Math.sqrt(distance*distance+24*24);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
double A = -211149.992;
|
||||||
|
double B = -1.19943;
|
||||||
|
double C = 3720.15909;
|
||||||
|
|
||||||
|
return A * Math.pow(x, B) + C;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,104 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import android.util.Size;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.vision.VisionPortal;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
public class AprilTagWebcam {
|
||||||
|
|
||||||
|
private AprilTagProcessor aprilTagProcessor;
|
||||||
|
private VisionPortal visionPortal;
|
||||||
|
private List<AprilTagDetection> detectedTags = new ArrayList<>();
|
||||||
|
private MultipleTelemetry telemetry;
|
||||||
|
public void init(Robot robot, MultipleTelemetry TELE){
|
||||||
|
|
||||||
|
this.telemetry = TELE;
|
||||||
|
|
||||||
|
aprilTagProcessor = new AprilTagProcessor.Builder()
|
||||||
|
.setDrawTagID(true)
|
||||||
|
.setDrawTagOutline(true)
|
||||||
|
.setDrawAxes(true)
|
||||||
|
.setDrawCubeProjection(true)
|
||||||
|
.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES)
|
||||||
|
.build();
|
||||||
|
|
||||||
|
VisionPortal.Builder builder = new VisionPortal.Builder();
|
||||||
|
builder.setCamera(robot.webcam);
|
||||||
|
builder.setCameraResolution(new Size(640, 480));
|
||||||
|
builder.addProcessor(aprilTagProcessor);
|
||||||
|
|
||||||
|
visionPortal = builder.build();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
detectedTags = aprilTagProcessor.getDetections();
|
||||||
|
}
|
||||||
|
|
||||||
|
public List<AprilTagDetection> getDetectedTags() {
|
||||||
|
return detectedTags;
|
||||||
|
}
|
||||||
|
|
||||||
|
public AprilTagDetection getTagById(int id){
|
||||||
|
for (AprilTagDetection detection : detectedTags) {
|
||||||
|
if (detection.id ==id){
|
||||||
|
return detection;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void stop(){
|
||||||
|
if (visionPortal != null){
|
||||||
|
visionPortal.close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//Helper Functions
|
||||||
|
|
||||||
|
public void displayDetectionTelemetry (AprilTagDetection detectedId){
|
||||||
|
if (detectedId ==null){return;}
|
||||||
|
|
||||||
|
if (detectedId.metadata != null) {
|
||||||
|
telemetry.addLine(String.format("\n==== (ID %d) %s", detectedId.id, detectedId.metadata.name));
|
||||||
|
telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", detectedId.ftcPose.x, detectedId.ftcPose.y, detectedId.ftcPose.z));
|
||||||
|
telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", detectedId.ftcPose.pitch, detectedId.ftcPose.roll, detectedId.ftcPose.yaw));
|
||||||
|
telemetry.addLine(String.format("RBE %6.1f %6.1f %6.1f (inch, deg, deg)", detectedId.ftcPose.range, detectedId.ftcPose.bearing, detectedId.ftcPose.elevation));
|
||||||
|
} else {
|
||||||
|
telemetry.addLine(String.format("\n==== (ID %d) Unknown", detectedId.id));
|
||||||
|
telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detectedId.center.x, detectedId.center.y));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void displayAllTelemetry (){
|
||||||
|
if (detectedTags ==null){return;}
|
||||||
|
|
||||||
|
telemetry.addData("# AprilTags Detected", detectedTags.size());
|
||||||
|
|
||||||
|
|
||||||
|
for (AprilTagDetection detection : detectedTags) {
|
||||||
|
if (detection.metadata != null) {
|
||||||
|
telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name));
|
||||||
|
telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", detection.ftcPose.x, detection.ftcPose.y, detection.ftcPose.z));
|
||||||
|
telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", detection.ftcPose.pitch, detection.ftcPose.roll, detection.ftcPose.yaw));
|
||||||
|
telemetry.addLine(String.format("RBE %6.1f %6.1f %6.1f (inch, deg, deg)", detection.ftcPose.range, detection.ftcPose.bearing, detection.ftcPose.elevation));
|
||||||
|
} else {
|
||||||
|
telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id));
|
||||||
|
telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y));
|
||||||
|
}
|
||||||
|
} // end for() loop
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
@@ -1,25 +1,34 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
import com.qualcomm.robotcore.hardware.I2cDeviceSynchSimple;
|
import com.qualcomm.robotcore.hardware.I2cDeviceSynchSimple;
|
||||||
|
|
||||||
@Disabled
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
public class ConfigureColorRangefinder extends LinearOpMode {
|
public class ConfigureColorRangefinder extends LinearOpMode {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public static double lowerBound = 80;
|
||||||
|
public static double higherBound = 120;
|
||||||
|
|
||||||
|
public static int led = 0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
ColorRangefinder crf = new ColorRangefinder(hardwareMap.get(RevColorSensorV3.class, "Color"));
|
ColorRangefinder crf = new ColorRangefinder(hardwareMap.get(RevColorSensorV3.class, "color"));
|
||||||
waitForStart();
|
waitForStart();
|
||||||
/* Using this example configuration, you can detect both artifact colors based on which pin is reading true:
|
/* Using this example configuration, you can detect both artifact colors based on which pin is reading true:
|
||||||
pin0 --> purple
|
pin0 --> purple
|
||||||
pin1 --> green */
|
pin1 --> green */
|
||||||
crf.setPin0Digital(ColorRangefinder.DigitalMode.HSV, 160 / 360.0 * 255, 190 / 360.0 * 255); // purple
|
crf.setPin0Digital(ColorRangefinder.DigitalMode.DISTANCE, 3, 20);
|
||||||
crf.setPin0DigitalMaxDistance(ColorRangefinder.DigitalMode.HSV, 25); // 10mm or closer requirement
|
crf.setPin1Digital(ColorRangefinder.DigitalMode.HSV, lowerBound, higherBound); // green
|
||||||
crf.setPin1Digital(ColorRangefinder.DigitalMode.HSV, 110 / 360.0 * 255, 140 / 360.0 * 255); // green
|
crf.setPin1DigitalMaxDistance(ColorRangefinder.DigitalMode.HSV, 25); //25 mm or closer
|
||||||
crf.setPin1DigitalMaxDistance(ColorRangefinder.DigitalMode.HSV, 25); // 10mm or closer requirement
|
crf.setLedBrightness(led);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,89 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
|
||||||
|
public class Flywheel {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double velo = 0.0;
|
||||||
|
double velo1 = 0.0;
|
||||||
|
double velo2 = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
|
double powPID = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public Flywheel (HardwareMap hardwareMap) {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getVelo () {
|
||||||
|
return velo;
|
||||||
|
}
|
||||||
|
public double getVelo1 () {
|
||||||
|
return velo1;
|
||||||
|
}
|
||||||
|
public double getVelo2 () {
|
||||||
|
return velo2;
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean getSteady() {
|
||||||
|
return steady;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set the robot PIDF for the next cycle.
|
||||||
|
public void setPIDF(double p, double i, double d, double f) {
|
||||||
|
robot.shooterPIDF.p = p;
|
||||||
|
robot.shooterPIDF.i = i;
|
||||||
|
robot.shooterPIDF.d = d;
|
||||||
|
robot.shooterPIDF.f = f;
|
||||||
|
}
|
||||||
|
private double getTimeSeconds ()
|
||||||
|
{
|
||||||
|
return (double) System.currentTimeMillis()/1000.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Convert from RPM to Ticks per Second
|
||||||
|
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
||||||
|
|
||||||
|
// Convert from Ticks per Second to RPM
|
||||||
|
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||||
|
|
||||||
|
public double manageFlywheel(double commandedVelocity) {
|
||||||
|
targetVelocity = commandedVelocity;
|
||||||
|
|
||||||
|
// Turn PIDF for Target Velocities
|
||||||
|
//robot.shooterPIDF.p = P;
|
||||||
|
//robot.shooterPIDF.i = I;
|
||||||
|
//robot.shooterPIDF.d = D;
|
||||||
|
//robot.shooterPIDF.f = F;
|
||||||
|
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||||
|
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||||
|
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
|
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
|
|
||||||
|
// Record Current Velocity
|
||||||
|
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||||
|
velo2 = TPS_to_RPM(robot.shooter1.getVelocity()); // Possible error: should it be shooter2 not shooter1?
|
||||||
|
velo = Math.max(velo1,velo2);
|
||||||
|
|
||||||
|
// really should be a running average of the last 5
|
||||||
|
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
||||||
|
|
||||||
|
return powPID;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,110 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class FlywheelV2 {
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
double initPos1 = 0.0;
|
||||||
|
double initPos2 = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double currentPos1 = 0.0;
|
||||||
|
double currentPos2 = 0.0;
|
||||||
|
double velo = 0.0;
|
||||||
|
double velo1 = 0.0;
|
||||||
|
double velo1a = 0.0;
|
||||||
|
double velo1b = 0.0;
|
||||||
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
|
double powPID = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
|
||||||
|
public FlywheelV2() {
|
||||||
|
//robot = new Robot(hardwareMap);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getVelo(double shooter1CurPos, double shooter2CurPos) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 2 == 0) {
|
||||||
|
velo5 = velo4;
|
||||||
|
velo4 = velo3;
|
||||||
|
velo3 = velo2;
|
||||||
|
velo2 = velo1;
|
||||||
|
|
||||||
|
currentPos1 = shooter1CurPos / 28;
|
||||||
|
currentPos2 = shooter2CurPos / 28;
|
||||||
|
stamp = getTimeSeconds(); //getRuntime();
|
||||||
|
velo1a = 60 * ((currentPos1 - initPos1) / (stamp - stamp1));
|
||||||
|
velo1b = 60 * ((currentPos2 - initPos2) / (stamp - stamp1));
|
||||||
|
initPos1 = currentPos1;
|
||||||
|
initPos2 = currentPos2;
|
||||||
|
stamp1 = stamp;
|
||||||
|
|
||||||
|
if (velo1a < 200){
|
||||||
|
velo1 = velo1b;
|
||||||
|
} else if (velo1b < 200){
|
||||||
|
velo1 = velo1a;
|
||||||
|
} else {
|
||||||
|
velo1 = (velo1a + velo1b) / 2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return ((velo1 + velo2 + velo3 + velo4 + velo5) / 5);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getVelo1() { return (velo1a + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||||
|
|
||||||
|
public double getVelo2() { return (velo1b + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||||
|
|
||||||
|
public boolean getSteady() {
|
||||||
|
return steady;
|
||||||
|
}
|
||||||
|
|
||||||
|
private double getTimeSeconds() {
|
||||||
|
return (double) System.currentTimeMillis() / 1000.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double manageFlywheel(int commandedVelocity, double shooter1CurPos, double shooter2CurPos) {
|
||||||
|
targetVelocity = commandedVelocity;
|
||||||
|
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
||||||
|
// Flywheel PID code here
|
||||||
|
if (targetVelocity - velo > 4500) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - targetVelocity > 4500) {
|
||||||
|
powPID = 0.0;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
double a = 2539.07863;
|
||||||
|
double c = 1967.6498;
|
||||||
|
double d = -0.289647;
|
||||||
|
double h = -1.1569;
|
||||||
|
|
||||||
|
double feed = Math.log10((a / (targetVelocity + c)) + d) / h;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = targetVelocity - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||||
|
|
||||||
|
return powPID;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,79 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class PositionalServoProgrammer extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
|
public static double spindexPos = 0.501;
|
||||||
|
public static double spindexPow = 0.0;
|
||||||
|
public static double spinHoldPow = 0.0;
|
||||||
|
public static double turretPos = 0.501;
|
||||||
|
public static double turretPow = 0.0;
|
||||||
|
public static double turrHoldPow = 0.0;
|
||||||
|
public static double transferPos = 0.501;
|
||||||
|
public static double hoodPos = 0.501;
|
||||||
|
public static int mode = 0; //0 for positional, 1 for power
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
while (opModeIsActive()){
|
||||||
|
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos) && mode == 0){
|
||||||
|
double pos = servo.setSpinPos(spindexPos);
|
||||||
|
robot.spin1.setPower(pos);
|
||||||
|
robot.spin2.setPower(-pos);
|
||||||
|
} else if (mode == 0){
|
||||||
|
robot.spin1.setPower(spinHoldPow);
|
||||||
|
robot.spin2.setPower(spinHoldPow);
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(spindexPow);
|
||||||
|
robot.spin2.setPower(-spindexPow);
|
||||||
|
}
|
||||||
|
if (turretPos != 0.501){
|
||||||
|
robot.turr1.setPosition(turretPos);
|
||||||
|
robot.turr2.setPosition(1-turretPos);
|
||||||
|
}
|
||||||
|
if (transferPos != 0.501){
|
||||||
|
robot.transferServo.setPosition(transferPos);
|
||||||
|
}
|
||||||
|
if (hoodPos != 0.501){
|
||||||
|
robot.hood.setPosition(hoodPos);
|
||||||
|
}
|
||||||
|
// To check configuration of spindexer:
|
||||||
|
// Set "mode" to 1 and spindexPow to 0.1
|
||||||
|
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
||||||
|
// Do the previous test again to confirm
|
||||||
|
// Set "mode" to 0 but keep spindexPos at 0.501
|
||||||
|
// Manually turn the spindexer until "spindexer pos" is set close to 0
|
||||||
|
// Check each spindexer voltage:
|
||||||
|
// If "spindexer voltage 1" is closer to 0 than "spindexer voltage 2," then you are done!
|
||||||
|
// If "spindexer voltage 2" is closer to 0 than "spindexer voltage 1," swap the two spindexer analog inputs in the configuration, DO NOT TOUCH THE ACTUAL CODE
|
||||||
|
//TODO: @KeshavAnandCode do the above please
|
||||||
|
|
||||||
|
TELE.addData("spindexer pos", servo.getSpinPos());
|
||||||
|
TELE.addData("turret pos", servo.getTurrPos());
|
||||||
|
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
||||||
|
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||||
|
TELE.addData("hood pos", robot.hood.getPosition());
|
||||||
|
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||||
|
TELE.addData("turret voltage", robot.turr1Pos.getCurrentPosition());
|
||||||
|
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,19 +1,128 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
|
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||||
|
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||||
|
import com.qualcomm.robotcore.hardware.CRServo;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||||
|
|
||||||
public class Robot {
|
public class Robot {
|
||||||
|
|
||||||
//Initialize Public Components
|
//Initialize Public Components
|
||||||
|
|
||||||
public Limelight3A limelight3A;
|
public DcMotorEx frontLeft;
|
||||||
|
public DcMotorEx frontRight;
|
||||||
|
public DcMotorEx backLeft;
|
||||||
|
public DcMotorEx backRight;
|
||||||
|
public DcMotorEx intake;
|
||||||
|
public DcMotorEx transfer;
|
||||||
|
public PIDFCoefficients shooterPIDF;
|
||||||
|
public double shooterPIDF_P = 10.0;
|
||||||
|
public double shooterPIDF_I = 0.6;
|
||||||
|
public double shooterPIDF_D = 5.0;
|
||||||
|
public double shooterPIDF_F = 10.0;
|
||||||
|
|
||||||
public Robot (HardwareMap hardwareMap) {
|
public double[] shooterPIDF_StepSizes = {10.0,1.0,0.001, 0.0001};
|
||||||
|
public DcMotorEx shooter1;
|
||||||
|
public DcMotorEx shooter2;
|
||||||
|
public Servo hood;
|
||||||
|
public Servo transferServo;
|
||||||
|
public Servo turr1;
|
||||||
|
public Servo turr2;
|
||||||
|
public CRServo spin1;
|
||||||
|
public CRServo spin2;
|
||||||
|
public AnalogInput spin1Pos;
|
||||||
|
public AnalogInput spin2Pos;
|
||||||
|
public DcMotorEx turr1Pos;
|
||||||
|
public AnalogInput transferServoPos;
|
||||||
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
|
public WebcamName webcam;
|
||||||
|
public RevColorSensorV3 color1;
|
||||||
|
public RevColorSensorV3 color2;
|
||||||
|
public RevColorSensorV3 color3;
|
||||||
|
public Limelight3A limelight;
|
||||||
|
|
||||||
|
public static boolean usingLimelight = true;
|
||||||
|
|
||||||
|
public static boolean usingCamera = true;
|
||||||
|
|
||||||
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
//Define components w/ hardware map
|
//Define components w/ hardware map
|
||||||
|
//TODO: fix the configuration of these - I trust you to figure it out yourself @KeshavAnandCode
|
||||||
|
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
|
||||||
|
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
||||||
|
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
||||||
|
backRight = hardwareMap.get(DcMotorEx.class, "br");
|
||||||
|
frontLeft.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
backLeft.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
limelight3A = hardwareMap.get(Limelight3A.class, "limelight");
|
frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
|
||||||
|
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
||||||
|
|
||||||
|
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
||||||
|
|
||||||
|
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||||
|
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
||||||
|
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
shooterPIDF = new PIDFCoefficients(shooterPIDF_P,shooterPIDF_I , shooterPIDF_D, shooterPIDF_F);
|
||||||
|
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||||
|
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||||
|
|
||||||
|
hood = hardwareMap.get(Servo.class, "hood");
|
||||||
|
|
||||||
|
turr1 = hardwareMap.get(Servo.class, "t1");
|
||||||
|
|
||||||
|
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||||
|
|
||||||
|
turr1Pos = intake; // Encoder of turret plugged in intake port
|
||||||
|
|
||||||
|
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
||||||
|
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||||
|
|
||||||
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
|
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
||||||
|
|
||||||
|
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||||
|
|
||||||
|
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||||
|
|
||||||
|
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
||||||
|
|
||||||
|
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
||||||
|
|
||||||
|
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
||||||
|
|
||||||
|
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
|
||||||
|
|
||||||
|
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||||
|
|
||||||
|
if (usingLimelight){
|
||||||
|
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
|
} else if (usingCamera){
|
||||||
|
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||||
|
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,60 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class Servos {
|
||||||
|
//PID constants
|
||||||
|
// TODO: get PIDF constants
|
||||||
|
public static double spinP = 3.3, spinI = 0, spinD = 0.1, spinF = 0.02;
|
||||||
|
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||||
|
public static double spin_scalar = 1.0086;
|
||||||
|
public static double spin_restPos = 0.0;
|
||||||
|
public static double turret_scalar = 1.009;
|
||||||
|
public static double turret_restPos = 0.0;
|
||||||
|
Robot robot;
|
||||||
|
PIDFController spinPID;
|
||||||
|
PIDFController turretPID;
|
||||||
|
|
||||||
|
public Servos(HardwareMap hardwareMap) {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
|
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
|
turretPID.setTolerance(0.001);
|
||||||
|
}
|
||||||
|
|
||||||
|
// In the code below, encoder = robot.servo.getVoltage()
|
||||||
|
|
||||||
|
public double getSpinPos() {
|
||||||
|
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
||||||
|
}
|
||||||
|
|
||||||
|
//TODO: PID warp so 0 and 1 are usable positions
|
||||||
|
public double setSpinPos(double pos) {
|
||||||
|
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
||||||
|
|
||||||
|
return spinPID.calculate(this.getSpinPos(), pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean spinEqual(double pos) {
|
||||||
|
return Math.abs(pos - this.getSpinPos()) < 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getTurrPos() {
|
||||||
|
return (double) ((double) robot.turr1Pos.getCurrentPosition() / 1024.0) * ((double) 44.0 / (double) 77.0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public double setTurrPos(double pos) {
|
||||||
|
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
|
return spinPID.calculate(this.getTurrPos(), pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean turretEqual(double pos) {
|
||||||
|
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,400 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
|
||||||
|
public class Spindexer {
|
||||||
|
Robot robot;
|
||||||
|
Servos servos;
|
||||||
|
Flywheel flywheel;
|
||||||
|
MecanumDrive drive;
|
||||||
|
double lastKnownSpinPos = 0.0;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
|
|
||||||
|
double spinCurrentPos = 0.0;
|
||||||
|
|
||||||
|
public int commandedIntakePosition = 0;
|
||||||
|
|
||||||
|
public double distanceRearCenter = 0.0;
|
||||||
|
public double distanceFrontDriver = 0.0;
|
||||||
|
public double distanceFrontPassenger = 0.0;
|
||||||
|
|
||||||
|
// For Use
|
||||||
|
enum RotatedBallPositionNames {
|
||||||
|
REARCENTER,
|
||||||
|
FRONTDRIVER,
|
||||||
|
FRONTPASSENGER
|
||||||
|
}
|
||||||
|
// Array of commandedIntakePositions with contents
|
||||||
|
// {RearCenter, FrontDriver, FrontPassenger}
|
||||||
|
static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}};
|
||||||
|
class spindexerBallRoatation {
|
||||||
|
int rearCenter = 0; // aka commanded Position
|
||||||
|
int frontDriver = 0;
|
||||||
|
int frontPassenger = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum IntakeState {
|
||||||
|
UNKNOWN,
|
||||||
|
INTAKE,
|
||||||
|
FINDNEXT,
|
||||||
|
MOVING,
|
||||||
|
FULL,
|
||||||
|
SHOOTNEXT,
|
||||||
|
SHOOTMOVING,
|
||||||
|
SHOOTWAIT,
|
||||||
|
};
|
||||||
|
|
||||||
|
public IntakeState currentIntakeState = IntakeState.UNKNOWN;
|
||||||
|
|
||||||
|
enum BallColor {
|
||||||
|
UNKNOWN,
|
||||||
|
GREEN,
|
||||||
|
PURPLE
|
||||||
|
};
|
||||||
|
|
||||||
|
class BallPosition {
|
||||||
|
boolean isEmpty = true;
|
||||||
|
int foundEmpty = 0;
|
||||||
|
BallColor ballColor = BallColor.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
BallPosition[] ballPositions = new BallPosition[3];
|
||||||
|
|
||||||
|
public boolean init () {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
public Spindexer(HardwareMap hardwareMap) {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
servos = new Servos(hardwareMap);
|
||||||
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
//TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
lastKnownSpinPos = servos.getSpinPos();
|
||||||
|
|
||||||
|
ballPositions[0] = new BallPosition();
|
||||||
|
ballPositions[1] = new BallPosition();
|
||||||
|
ballPositions[2] = new BallPosition();
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
double[] outakePositions =
|
||||||
|
{spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3};
|
||||||
|
|
||||||
|
double[] intakePositions =
|
||||||
|
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
||||||
|
|
||||||
|
public int counter = 0;
|
||||||
|
|
||||||
|
// private double getTimeSeconds ()
|
||||||
|
// {
|
||||||
|
// return (double) System.currentTimeMillis()/1000.0;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public double getPos() {
|
||||||
|
// robot.spin1Pos.getVoltage();
|
||||||
|
// robot.spin1Pos.getMaxVoltage();
|
||||||
|
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public void manageSpindexer() {
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
|
||||||
|
public void resetBallPosition (int pos) {
|
||||||
|
ballPositions[pos].isEmpty = true;
|
||||||
|
ballPositions[pos].foundEmpty = 0;
|
||||||
|
ballPositions[pos].ballColor = BallColor.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void resetSpindexer () {
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
resetBallPosition(i);
|
||||||
|
}
|
||||||
|
currentIntakeState = IntakeState.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Detects if a ball is found and what color.
|
||||||
|
// Returns true is there was a new ball found in Position 1
|
||||||
|
// FIXIT: Reduce number of times that we read the color sensors for loop times.
|
||||||
|
public boolean detectBalls() {
|
||||||
|
|
||||||
|
boolean newPos1Detection = false;
|
||||||
|
int spindexerBallPos = 0;
|
||||||
|
|
||||||
|
// Read Distances
|
||||||
|
distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
// Position 1
|
||||||
|
if (distanceRearCenter < 43) {
|
||||||
|
|
||||||
|
// Mark Ball Found
|
||||||
|
newPos1Detection = true;
|
||||||
|
|
||||||
|
// Detect which color
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
// FIXIT - Add filtering to improve accuracy.
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||||
|
} else {
|
||||||
|
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Position 2
|
||||||
|
// Find which ball position this is in the spindexer
|
||||||
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||||
|
if (distanceFrontDriver < 60) {
|
||||||
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
|
// FIXIT: Comment out for now due to loop time concerns
|
||||||
|
// double green = robot.color2.getNormalizedColors().green;
|
||||||
|
// double red = robot.color2.getNormalizedColors().red;
|
||||||
|
// double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
//
|
||||||
|
// double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
// if (gP >= 0.4) {
|
||||||
|
// b2 = 2; // purple
|
||||||
|
// } else {
|
||||||
|
// b2 = 1; // green
|
||||||
|
// }
|
||||||
|
} else {
|
||||||
|
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||||
|
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||||
|
resetBallPosition(spindexerBallPos);
|
||||||
|
}
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty++;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Position 3
|
||||||
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
|
||||||
|
if (distanceFrontPassenger < 33) {
|
||||||
|
|
||||||
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
|
// FIXIT: Comment out for now due to loop time concerns
|
||||||
|
// double green = robot.color3.getNormalizedColors().green;
|
||||||
|
// double red = robot.color3.getNormalizedColors().red;
|
||||||
|
// double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
// double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
// if (gP >= 0.4) {
|
||||||
|
// b3 = 2; // purple
|
||||||
|
// } else {
|
||||||
|
// b3 = 1; // green
|
||||||
|
// }
|
||||||
|
} else {
|
||||||
|
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||||
|
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||||
|
resetBallPosition(spindexerBallPos);
|
||||||
|
}
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TELE.addData("Velocity", velo);
|
||||||
|
// TELE.addLine("Detecting");
|
||||||
|
// TELE.addData("Distance 1", s1D);
|
||||||
|
// TELE.addData("Distance 2", s2D);
|
||||||
|
// TELE.addData("Distance 3", s3D);
|
||||||
|
// TELE.addData("B1", b1);
|
||||||
|
// TELE.addData("B2", b2);
|
||||||
|
// TELE.addData("B3", b3);
|
||||||
|
// TELE.update();
|
||||||
|
|
||||||
|
return newPos1Detection;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void moveSpindexerToPos(double pos) {
|
||||||
|
spinCurrentPos = servos.getSpinPos();
|
||||||
|
|
||||||
|
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexPID);
|
||||||
|
robot.spin2.setPower(-spindexPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void stopSpindexer() {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isFull () {
|
||||||
|
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
||||||
|
}
|
||||||
|
public boolean processIntake() {
|
||||||
|
|
||||||
|
switch (currentIntakeState) {
|
||||||
|
case UNKNOWN:
|
||||||
|
// For now just set position ONE if UNKNOWN
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(intakePositions[0]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
break;
|
||||||
|
case INTAKE:
|
||||||
|
// Ready for intake and Detecting a New Ball
|
||||||
|
if (detectBalls()) {
|
||||||
|
ballPositions[commandedIntakePosition].isEmpty = false;
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
|
} else {
|
||||||
|
// Maintain Position
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case FINDNEXT:
|
||||||
|
// Find Next Open Position and start movement
|
||||||
|
double currentSpindexerPos = servos.getSpinPos();
|
||||||
|
double commandedtravelDistance = 2.0;
|
||||||
|
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||||
|
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 1
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||||
|
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 2
|
||||||
|
commandedIntakePosition = 1;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||||
|
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 3
|
||||||
|
commandedIntakePosition = 2;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||||
|
// Full
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||||
|
}
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MOVING:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||||
|
stopSpindexer();
|
||||||
|
detectBalls();
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FULL:
|
||||||
|
// Double Check Colors
|
||||||
|
detectBalls();
|
||||||
|
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
||||||
|
// Error handling found an empty spot, get it ready for a ball
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
|
}
|
||||||
|
// Maintain Position
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTNEXT:
|
||||||
|
// Find Next Open Position and start movement
|
||||||
|
if (!ballPositions[0].isEmpty) {
|
||||||
|
// Position 1
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty?
|
||||||
|
// Position 2
|
||||||
|
commandedIntakePosition = 1;
|
||||||
|
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty?
|
||||||
|
// Position 3
|
||||||
|
commandedIntakePosition = 2;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else {
|
||||||
|
// Empty return to intake state
|
||||||
|
currentIntakeState = IntakeState.FINDNEXT;
|
||||||
|
}
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTMOVING:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
||||||
|
ballPositions[commandedIntakePosition].isEmpty = true;
|
||||||
|
// Advance to next full position and wait
|
||||||
|
// commandedIntakePosition++;
|
||||||
|
// if (commandedIntakePosition > 2) {
|
||||||
|
// commandedIntakePosition = 0;
|
||||||
|
// }
|
||||||
|
// // Continue moving to next position
|
||||||
|
// servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
// currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTWAIT:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||||
|
stopSpindexer();
|
||||||
|
detectBalls();
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// Statements to execute if no case matches
|
||||||
|
}
|
||||||
|
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
||||||
|
//TELE.update();
|
||||||
|
// Signal a successful intake
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,8 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
public interface Subsystem {
|
|
||||||
|
|
||||||
public void update();
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,10 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Vars {
|
|
||||||
|
|
||||||
public static boolean USING_LL = false;
|
|
||||||
}
|
|
||||||
@@ -1,4 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils.functions;
|
|
||||||
|
|
||||||
public class DistanceToTarget {
|
|
||||||
}
|
|
||||||
@@ -1,181 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils.subsystems;
|
|
||||||
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLStatus;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Position;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Subsystem;
|
|
||||||
|
|
||||||
import java.util.ArrayList;
|
|
||||||
import java.util.List;
|
|
||||||
import java.util.Objects;
|
|
||||||
|
|
||||||
public class Limelight implements Subsystem {
|
|
||||||
|
|
||||||
private final Limelight3A limelight;
|
|
||||||
private final MultipleTelemetry telemetry;
|
|
||||||
|
|
||||||
private LLResult result;
|
|
||||||
private LLStatus status;
|
|
||||||
|
|
||||||
private boolean telemetryOn = false;
|
|
||||||
private String mode = "AT";
|
|
||||||
|
|
||||||
// ✅ Internal cached data
|
|
||||||
private Pose3D botpose;
|
|
||||||
|
|
||||||
private double captureLatency = 0.0;
|
|
||||||
private double targetingLatency = 0.0;
|
|
||||||
private double parseLatency = 0.0;
|
|
||||||
private double[] pythonOutput = new double[0];
|
|
||||||
|
|
||||||
private double tx = 0.0;
|
|
||||||
private double txnc = 0.0;
|
|
||||||
private double ty = 0.0;
|
|
||||||
private double tync = 0.0;
|
|
||||||
|
|
||||||
private List<LLResultTypes.BarcodeResult> barcodeResults = new ArrayList<>();
|
|
||||||
private List<LLResultTypes.ClassifierResult> classifierResults = new ArrayList<>();
|
|
||||||
private List<LLResultTypes.DetectorResult> detectorResults = new ArrayList<>();
|
|
||||||
private List<LLResultTypes.FiducialResult> fiducialResults = new ArrayList<>();
|
|
||||||
private List<LLResultTypes.ColorResult> colorResults = new ArrayList<>();
|
|
||||||
|
|
||||||
public Limelight(Robot robot, MultipleTelemetry tele) {
|
|
||||||
this.limelight = robot.limelight3A;
|
|
||||||
this.telemetry = tele;
|
|
||||||
limelight.pipelineSwitch(1);
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setPipeline(int pipeline) {limelight.pipelineSwitch(pipeline);}
|
|
||||||
|
|
||||||
public void setTelemetryOn(boolean state) { telemetryOn = state; }
|
|
||||||
|
|
||||||
public void setMode(String newMode) { this.mode = newMode; }
|
|
||||||
|
|
||||||
/** ✅ MAIN UPDATE LOOP */
|
|
||||||
@Override
|
|
||||||
public void update() {
|
|
||||||
result = limelight.getLatestResult();
|
|
||||||
status = limelight.getStatus();
|
|
||||||
|
|
||||||
if (result != null && (Objects.equals(status.getPipelineType(), "pipe_python") || result.isValid())){
|
|
||||||
// Refresh all cached values
|
|
||||||
botpose = result.getBotpose();
|
|
||||||
captureLatency = result.getCaptureLatency();
|
|
||||||
targetingLatency= result.getTargetingLatency();
|
|
||||||
parseLatency = result.getParseLatency();
|
|
||||||
pythonOutput = result.getPythonOutput();
|
|
||||||
tx = result.getTx();
|
|
||||||
txnc = result.getTxNC();
|
|
||||||
ty = result.getTy();
|
|
||||||
tync = result.getTyNC();
|
|
||||||
barcodeResults = result.getBarcodeResults();
|
|
||||||
classifierResults = result.getClassifierResults();
|
|
||||||
detectorResults = result.getDetectorResults();
|
|
||||||
fiducialResults = result.getFiducialResults();
|
|
||||||
colorResults = result.getColorResults();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (telemetryOn) telemetryUpdate();
|
|
||||||
}
|
|
||||||
|
|
||||||
/** ✅ Telemetry Output */
|
|
||||||
private void telemetryUpdate() {
|
|
||||||
// ✅ Use getters instead of directly accessing 'status' or cached fields
|
|
||||||
telemetry.addData("Name", "%s", getStatus().getName());
|
|
||||||
telemetry.addData("LL", "Temp: %.1fC, CPU: %.1f%%, FPS: %d",
|
|
||||||
getStatus().getTemp(),
|
|
||||||
getStatus().getCpu(),
|
|
||||||
(int) getStatus().getFps());
|
|
||||||
telemetry.addData("Pipeline", "Index: %d, Type: %s",
|
|
||||||
getStatus().getPipelineIndex(),
|
|
||||||
getStatus().getPipelineType());
|
|
||||||
telemetry.addData("ResultNull", result == null);
|
|
||||||
telemetry.addData("ResultValid", result.isValid());
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (result != null && result.isValid()) {
|
|
||||||
telemetry.addData("LL Latency", getTotalLatency());
|
|
||||||
telemetry.addData("Capture Latency", getCaptureLatency());
|
|
||||||
telemetry.addData("Targeting Latency", getTargetingLatency());
|
|
||||||
telemetry.addData("Parse Latency", getParseLatency());
|
|
||||||
telemetry.addData("PythonOutput", java.util.Arrays.toString(getPythonOutput()));
|
|
||||||
telemetry.addData("tx", getTx());
|
|
||||||
telemetry.addData("txnc", getTxNC());
|
|
||||||
telemetry.addData("ty", getTy());
|
|
||||||
telemetry.addData("tync", getTyNC());
|
|
||||||
telemetry.addData("Botpose", getBotPose().toString());
|
|
||||||
|
|
||||||
|
|
||||||
if (Objects.equals(mode, "BR"))
|
|
||||||
for (LLResultTypes.BarcodeResult br : getBarcodeResults())
|
|
||||||
telemetry.addData("Barcode", "Data: %s", br.getData());
|
|
||||||
|
|
||||||
if (Objects.equals(mode, "CL"))
|
|
||||||
for (LLResultTypes.ClassifierResult cr : getClassifierResults())
|
|
||||||
telemetry.addData("Classifier", "Class: %s, Confidence: %.2f",
|
|
||||||
cr.getClassName(), cr.getConfidence());
|
|
||||||
|
|
||||||
if (Objects.equals(mode, "DE"))
|
|
||||||
for (LLResultTypes.DetectorResult dr : getDetectorResults())
|
|
||||||
telemetry.addData("Detector", "Class: %s, Area: %.2f",
|
|
||||||
dr.getClassName(), dr.getTargetArea());
|
|
||||||
|
|
||||||
if (Objects.equals(mode, "FI"))
|
|
||||||
for (LLResultTypes.FiducialResult fr : getFiducialResults())
|
|
||||||
telemetry.addData("Fiducial", "ID: %d, Family: %s, X: %.2f, Y: %.2f",
|
|
||||||
fr.getFiducialId(), fr.getFamily(),
|
|
||||||
fr.getTargetXDegrees(), fr.getTargetYDegrees());
|
|
||||||
|
|
||||||
if (Objects.equals(mode, "CO"))
|
|
||||||
for (LLResultTypes.ColorResult cr : getColorResults())
|
|
||||||
telemetry.addData("Color", "X: %.2f, Y: %.2f",
|
|
||||||
cr.getTargetXDegrees(), cr.getTargetYDegrees());
|
|
||||||
} else {
|
|
||||||
telemetry.addData("Limelight", "No data available");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// ✅ Getter methods (for use anywhere else in your code)
|
|
||||||
|
|
||||||
public Pose3D getBotPose() {
|
|
||||||
if (botpose == null) {
|
|
||||||
botpose = new Pose3D(
|
|
||||||
new Position(),
|
|
||||||
new YawPitchRollAngles(AngleUnit.DEGREES, 0.0, 0.0, 0.0, 0L)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
return botpose;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getCaptureLatency() { return captureLatency; }
|
|
||||||
public double getTargetingLatency() { return targetingLatency; }
|
|
||||||
public double getTotalLatency() { return captureLatency + targetingLatency; }
|
|
||||||
public double getParseLatency() { return parseLatency; }
|
|
||||||
public double[] getPythonOutput() { return pythonOutput; }
|
|
||||||
|
|
||||||
public double getTx() { return tx; }
|
|
||||||
public double getTxNC() { return txnc; }
|
|
||||||
public double getTy() { return ty; }
|
|
||||||
public double getTyNC() { return tync; }
|
|
||||||
|
|
||||||
public List<LLResultTypes.BarcodeResult> getBarcodeResults() { return barcodeResults; }
|
|
||||||
public List<LLResultTypes.ClassifierResult> getClassifierResults() { return classifierResults; }
|
|
||||||
public List<LLResultTypes.DetectorResult> getDetectorResults() { return detectorResults; }
|
|
||||||
public List<LLResultTypes.FiducialResult> getFiducialResults() { return fiducialResults; }
|
|
||||||
public List<LLResultTypes.ColorResult> getColorResults() { return colorResults; }
|
|
||||||
|
|
||||||
public LLStatus getStatus() { return status; }
|
|
||||||
public LLResult getRawResult() { return result; }
|
|
||||||
}
|
|
||||||
Reference in New Issue
Block a user