Compare commits
50 Commits
8840205fb3
...
daniel
| Author | SHA1 | Date | |
|---|---|---|---|
| d32033a015 | |||
| a869d4b7a0 | |||
| 00966f98ba | |||
| 88e1c428a5 | |||
| 4bbe5f218c | |||
| b0bc7b7b5b | |||
| 46f1bd5191 | |||
| 087c629d08 | |||
| c91828f899 | |||
| 84c9b08205 | |||
| d639530fa9 | |||
| bfa8b52ebc | |||
| 3b342d1656 | |||
| 582ea86ac5 | |||
| 77b42acdda | |||
| 8d75b245e3 | |||
| e5ba0947e3 | |||
| f8222e292f | |||
| 31b98cc8a1 | |||
| b6c8ea1a28 | |||
| 5e41560fd5 | |||
| 8aa1954fbf | |||
| 7246e648d9 | |||
| dedc7e9b97 | |||
| 2e456f653d | |||
| f08afd928a | |||
| 0df3a68920 | |||
| abe5d0899f | |||
| 7f968de6a8 | |||
| 331ec2fa0b | |||
| deda28dd37 | |||
| 9e3aadc8de | |||
| 37fa917b68 | |||
| 40e415a967 | |||
| b026a597b4 | |||
| 0cdae76697 | |||
| 7e01e52f6d | |||
| a7031232cf | |||
| 6ad7d46580 | |||
| ee2208922b | |||
| 03d72af8d2 | |||
| bb821d9108 | |||
| c517443459 | |||
| 34f2f4b593 | |||
| de096a925c | |||
| 96f4f1c639 | |||
| 77a68937f1 | |||
| a1b1cb99f6 | |||
| e7c18a671a | |||
| 0c81ca6a1a |
@@ -23,19 +23,6 @@ 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
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,921 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootY;
|
|
||||||
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.bhPrep;
|
|
||||||
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.bxPrep;
|
|
||||||
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.byPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootY;
|
|
||||||
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.rhPrep;
|
|
||||||
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.rxPrep;
|
|
||||||
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.ryPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
|
||||||
|
|
||||||
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.TrajectoryActionBuilder;
|
|
||||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.Poses_V2;
|
|
||||||
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 org.firstinspires.ftc.teamcode.utils.Spindexer;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class Auto_LT_Close_12Ball extends LinearOpMode {
|
|
||||||
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
|
|
||||||
public static double autoSpinStartPos = 0.2;
|
|
||||||
public static double shoot0SpinSpeedIncrease = 0.014;
|
|
||||||
|
|
||||||
public static double spindexerSpeedIncrease = 0.02;
|
|
||||||
|
|
||||||
public static double obeliskTurrPos = 0.53;
|
|
||||||
public static double normalIntakeTime = 3.0;
|
|
||||||
public static double shoot1Turr = 0.57;
|
|
||||||
public static double shoot0XTolerance = 1.0;
|
|
||||||
public static double turretShootPos = 0.53;
|
|
||||||
public static double shootAllTime = 1.8;
|
|
||||||
public static double shoot0Time = 1.6;
|
|
||||||
public static double intake1Time = 3.0;
|
|
||||||
public static double flywheel0Time = 3.5;
|
|
||||||
public static double pickup1Speed = 25;
|
|
||||||
// ---- SECOND SHOT / PICKUP ----
|
|
||||||
public static double shoot1Vel = 2300;
|
|
||||||
public static double shoot1Hood = 0.93;
|
|
||||||
|
|
||||||
public static double shootAllVelocity = 2500;
|
|
||||||
public static double shootAllHood = 0.78;
|
|
||||||
// ---- PICKUP TIMING ----
|
|
||||||
public static double pickup1Time = 3.0;
|
|
||||||
// ---- PICKUP POSITION TOLERANCES ----
|
|
||||||
public static double pickup1XTolerance = 2.0;
|
|
||||||
public static double pickup1YTolerance = 2.0;
|
|
||||||
// ---- OBELISK DETECTION ----
|
|
||||||
public static double obelisk1Time = 1.5;
|
|
||||||
public static double obelisk1XTolerance = 2.0;
|
|
||||||
public static double obelisk1YTolerance = 2.0;
|
|
||||||
public static double shoot1ToleranceX = 2.0;
|
|
||||||
public static double shoot1ToleranceY = 2.0;
|
|
||||||
public static double shoot1Time = 2.0;
|
|
||||||
public static double shootCycleTime = 2.5;
|
|
||||||
public int motif = 0;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Servos servos;
|
|
||||||
Spindexer spindexer;
|
|
||||||
Flywheel flywheel;
|
|
||||||
Turret turret;
|
|
||||||
Targeting targeting;
|
|
||||||
Targeting.Settings targetingSettings;
|
|
||||||
private double x1, y1, h1;
|
|
||||||
|
|
||||||
private double x2a, y2a, h2a, t2a;
|
|
||||||
|
|
||||||
private double x2b, y2b, h2b, t2b;
|
|
||||||
private double x2c, y2c, h2c, t2c;
|
|
||||||
|
|
||||||
private double x3a, y3a, h3a;
|
|
||||||
private double x3b, y3b, h3b;
|
|
||||||
private double x4a, y4a, h4a;
|
|
||||||
private double x4b, y4b, h4b;
|
|
||||||
|
|
||||||
private double xShoot, yShoot, hShoot;
|
|
||||||
private double xGate, yGate, hGate;
|
|
||||||
private double xPrep, yPrep, hPrep;
|
|
||||||
|
|
||||||
private double shoot1Tangent;
|
|
||||||
|
|
||||||
|
|
||||||
public Action prepareShootAll(double time) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
turret.manualSetTurret(turretShootPos);
|
|
||||||
|
|
||||||
robot.intake.setPower(-((System.currentTimeMillis() - stamp)) / 1000);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return (System.currentTimeMillis() - stamp) < (time * 1000);
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
|
|
||||||
return new Action() {
|
|
||||||
int ticker = 1;
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
|
|
||||||
double velo = vel;
|
|
||||||
|
|
||||||
int shooterTicker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
Poses_V2.teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.intake.setPower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < shootTime) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action shootAllAuto(double shootTime, double spindexSpeed) {
|
|
||||||
return new Action() {
|
|
||||||
int ticker = 1;
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
|
|
||||||
double velo = 0.0;
|
|
||||||
|
|
||||||
int shooterTicker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
Poses_V2.teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.intake.setPower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < shootTime) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.processIntake();
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return (System.currentTimeMillis() - stamp) < (intakeTime * 1000);
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action detectObelisk(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance,
|
|
||||||
double turrPos
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
robot.turr1.setPosition(turrPos);
|
|
||||||
robot.turr2.setPosition(1 - turrPos);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageFlywheel(
|
|
||||||
double vel,
|
|
||||||
double hoodPos,
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
robot.hood.setPosition(hoodPos);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageShooterAuto(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
robot.hood.setPosition(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageFlywheelAuto(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
|
|
||||||
robot.hood.setPosition(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(
|
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
|
||||||
);
|
|
||||||
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
|
||||||
|
|
||||||
targeting = new Targeting();
|
|
||||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
|
||||||
|
|
||||||
spindexer = new Spindexer(hardwareMap);
|
|
||||||
|
|
||||||
servos = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
|
|
||||||
turret.manualSetTurret(0.4);
|
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
|
||||||
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot0 = null;
|
|
||||||
TrajectoryActionBuilder pickup1 = null;
|
|
||||||
TrajectoryActionBuilder shoot1 = null;
|
|
||||||
TrajectoryActionBuilder pickup2 = null;
|
|
||||||
TrajectoryActionBuilder shoot2 = null;
|
|
||||||
TrajectoryActionBuilder pickup3 = null;
|
|
||||||
TrajectoryActionBuilder shoot3 = null;
|
|
||||||
|
|
||||||
robot.limelight.start();
|
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
robot.hood.setPosition(shoot0Hood);
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
robot.light.setPosition(0.28);
|
|
||||||
|
|
||||||
// ---- FIRST SHOT ----
|
|
||||||
x1 = rx1;
|
|
||||||
y1 = ry1;
|
|
||||||
h1 = rh1;
|
|
||||||
|
|
||||||
// ---- PICKUP PATH ----
|
|
||||||
x2a = rx2a;
|
|
||||||
y2a = ry2a;
|
|
||||||
h2a = rh2a;
|
|
||||||
x2b = rx2b;
|
|
||||||
y2b = ry2b;
|
|
||||||
h2b = rh2b;
|
|
||||||
x3a = rx3a;
|
|
||||||
y3a = ry3a;
|
|
||||||
h3a = rh3a;
|
|
||||||
x3b = rx3b;
|
|
||||||
y3b = ry3b;
|
|
||||||
h3b = rh3b;
|
|
||||||
x4a = rx4a;
|
|
||||||
y4a = ry4a;
|
|
||||||
h4a = rh4a;
|
|
||||||
x4b = rx4b;
|
|
||||||
y4b = ry4b;
|
|
||||||
h4b = rh4b;
|
|
||||||
xPrep = rxPrep;
|
|
||||||
yPrep = ryPrep;
|
|
||||||
hPrep = rhPrep;
|
|
||||||
xShoot = rShootX;
|
|
||||||
yShoot = rShootY;
|
|
||||||
hShoot = rShootH;
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.light.setPosition(0.6);
|
|
||||||
|
|
||||||
// ---- FIRST SHOT ----
|
|
||||||
x1 = bx1;
|
|
||||||
y1 = by1;
|
|
||||||
h1 = bh1;
|
|
||||||
|
|
||||||
// ---- PICKUP PATH ----
|
|
||||||
x2a = bx2a;
|
|
||||||
y2a = by2a;
|
|
||||||
h2a = bh2a;
|
|
||||||
x2b = bx2b;
|
|
||||||
y2b = by2b;
|
|
||||||
h2b = bh2b;
|
|
||||||
x3a = bx3a;
|
|
||||||
y3a = by3a;
|
|
||||||
h3a = bh3a;
|
|
||||||
x3b = bx3b;
|
|
||||||
y3b = by3b;
|
|
||||||
h3b = bh3b;
|
|
||||||
x4a = bx4a;
|
|
||||||
y4a = by4a;
|
|
||||||
h4a = bh4a;
|
|
||||||
x4b = bx4b;
|
|
||||||
y4b = by4b;
|
|
||||||
h4b = bh4b;
|
|
||||||
|
|
||||||
xPrep = bxPrep;
|
|
||||||
yPrep = byPrep;
|
|
||||||
hPrep = bhPrep;
|
|
||||||
xShoot = bShootX;
|
|
||||||
yShoot = bShootY;
|
|
||||||
hShoot = bShootH;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
|
|
||||||
new TranslationalVelConstraint(pickup1Speed));
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x3a, y3a), h3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(x3b, y3b), h3b,
|
|
||||||
new TranslationalVelConstraint(pickup1Speed));
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, h3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
|
||||||
|
|
||||||
pickup3 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x4a, y4a), h4a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(x4b, y4b), h4b,
|
|
||||||
new TranslationalVelConstraint(pickup1Speed));
|
|
||||||
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, h4b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
TELE.addData("Red?", redAlliance);
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
assert shoot0 != null;
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot0.build(),
|
|
||||||
manageFlywheel(
|
|
||||||
shoot0Vel,
|
|
||||||
shoot0Hood,
|
|
||||||
flywheel0Time,
|
|
||||||
x1,
|
|
||||||
0.501,
|
|
||||||
shoot0XTolerance,
|
|
||||||
0.501
|
|
||||||
)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
shootAll((int) shoot0Vel, shoot0Time, shoot0SpinSpeedIncrease)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup1.build(),
|
|
||||||
manageFlywheel(
|
|
||||||
shootAllVelocity,
|
|
||||||
shootAllHood,
|
|
||||||
pickup1Time,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
pickup1XTolerance,
|
|
||||||
pickup1YTolerance
|
|
||||||
),
|
|
||||||
intake(intake1Time)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheel(
|
|
||||||
shootAllVelocity,
|
|
||||||
shootAllHood,
|
|
||||||
shoot1Time,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shoot1.build(),
|
|
||||||
prepareShootAll(shoot1Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageShooterAuto(
|
|
||||||
shootAllTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup2.build(),
|
|
||||||
manageShooterAuto(
|
|
||||||
normalIntakeTime,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
pickup1XTolerance,
|
|
||||||
pickup1YTolerance
|
|
||||||
),
|
|
||||||
intake(normalIntakeTime)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheelAuto(
|
|
||||||
shootCycleTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shoot2.build(),
|
|
||||||
prepareShootAll(shootCycleTime)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageShooterAuto(
|
|
||||||
shootAllTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup3.build(),
|
|
||||||
manageShooterAuto(
|
|
||||||
normalIntakeTime,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
pickup1XTolerance,
|
|
||||||
pickup1YTolerance
|
|
||||||
),
|
|
||||||
intake(normalIntakeTime)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheelAuto(
|
|
||||||
shootCycleTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shoot3.build(),
|
|
||||||
prepareShootAll(shootCycleTime)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageShooterAuto(
|
|
||||||
shootAllTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
|
|
||||||
|
|
||||||
TELE.addLine("finished");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
sleep(2000);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,804 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bHGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShoot1Tangent;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootY;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bXGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bYGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rHGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShoot1Tangent;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootY;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rXGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rYGate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2c;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.teleStart;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
|
||||||
|
|
||||||
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.TrajectoryActionBuilder;
|
|
||||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
|
||||||
|
|
||||||
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 org.firstinspires.ftc.teamcode.utils.Spindexer;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
@Config
|
|
||||||
public class Auto_LT_Close_GateCycle extends LinearOpMode {
|
|
||||||
|
|
||||||
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
|
|
||||||
public static double autoSpinStartPos = 0.2;
|
|
||||||
public static double shoot0SpinSpeedIncrease = 0.014;
|
|
||||||
|
|
||||||
public static double spindexerSpeedIncrease = 0.02;
|
|
||||||
|
|
||||||
public static double obeliskTurrPos = 0.53;
|
|
||||||
public static double gatePickupTime = 3.0;
|
|
||||||
public static double shoot1Turr = 0.57;
|
|
||||||
public static double shoot0XTolerance = 1.0;
|
|
||||||
public static double turretShootPos = 0.72;
|
|
||||||
public static double shootAllTime = 1.8;
|
|
||||||
public static double shoot0Time = 1.6;
|
|
||||||
public static double intake1Time = 3.0;
|
|
||||||
public static double flywheel0Time = 3.5;
|
|
||||||
public static double pickup1Speed = 80.0;
|
|
||||||
// ---- SECOND SHOT / PICKUP ----
|
|
||||||
public static double shoot1Vel = 2300;
|
|
||||||
public static double shoot1Hood = 0.93;
|
|
||||||
|
|
||||||
public static double shootAllVelocity = 2500;
|
|
||||||
public static double shootAllHood = 0.78;
|
|
||||||
// ---- PICKUP TIMING ----
|
|
||||||
public static double pickup1Time = 3.0;
|
|
||||||
// ---- PICKUP POSITION TOLERANCES ----
|
|
||||||
public static double pickup1XTolerance = 2.0;
|
|
||||||
public static double pickup1YTolerance = 2.0;
|
|
||||||
// ---- OBELISK DETECTION ----
|
|
||||||
public static double obelisk1Time = 1.5;
|
|
||||||
public static double obelisk1XTolerance = 2.0;
|
|
||||||
public static double obelisk1YTolerance = 2.0;
|
|
||||||
public static double shoot1ToleranceX = 2.0;
|
|
||||||
public static double shoot1ToleranceY = 2.0;
|
|
||||||
public static double shoot1Time = 2.0;
|
|
||||||
public static double shootCycleTime = 2.5;
|
|
||||||
public int motif = 0;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Servos servos;
|
|
||||||
Spindexer spindexer;
|
|
||||||
Flywheel flywheel;
|
|
||||||
Turret turret;
|
|
||||||
Targeting targeting;
|
|
||||||
Targeting.Settings targetingSettings;
|
|
||||||
private double x1, y1, h1;
|
|
||||||
|
|
||||||
private double x2a, y2a, h2a, t2a;
|
|
||||||
|
|
||||||
private double x2b, y2b, h2b, t2b;
|
|
||||||
private double x2c, y2c, h2c, t2c;
|
|
||||||
|
|
||||||
private double xShoot, yShoot, hShoot;
|
|
||||||
private double xGate, yGate, hGate;
|
|
||||||
|
|
||||||
private double shoot1Tangent;
|
|
||||||
|
|
||||||
public Action prepareShootAll(double time) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
turret.manualSetTurret(turretShootPos);
|
|
||||||
|
|
||||||
robot.intake.setPower(-((System.currentTimeMillis() - stamp)) / 1000);
|
|
||||||
|
|
||||||
return (System.currentTimeMillis() - stamp) < (time * 1000);
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
|
|
||||||
return new Action() {
|
|
||||||
int ticker = 1;
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
|
|
||||||
double velo = vel;
|
|
||||||
|
|
||||||
int shooterTicker = 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 < shootTime) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action shootAllAuto(double shootTime, double spindexSpeed) {
|
|
||||||
return new Action() {
|
|
||||||
int ticker = 1;
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
|
|
||||||
double velo = 0.0;
|
|
||||||
|
|
||||||
int shooterTicker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("shooting");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
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 < shootTime) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.processIntake();
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
|
|
||||||
return (System.currentTimeMillis() - stamp) < (intakeTime * 1000);
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action detectObelisk(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance,
|
|
||||||
double turrPos
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
robot.turr1.setPosition(turrPos);
|
|
||||||
robot.turr2.setPosition(1 - turrPos);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageFlywheel(
|
|
||||||
double vel,
|
|
||||||
double hoodPos,
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
robot.hood.setPosition(hoodPos);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageShooterAuto(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
robot.hood.setPosition(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action manageFlywheelAuto(
|
|
||||||
double time,
|
|
||||||
double posX,
|
|
||||||
double posY,
|
|
||||||
double posXTolerance,
|
|
||||||
double posYTolerance
|
|
||||||
) {
|
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
|
||||||
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
|
|
||||||
robot.hood.setPosition(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
|
||||||
|
|
||||||
return !shouldFinish;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
hardwareMap.get(Servo.class, "light").setPosition(0);
|
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(
|
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
|
||||||
);
|
|
||||||
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
|
||||||
|
|
||||||
targeting = new Targeting();
|
|
||||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
|
||||||
|
|
||||||
spindexer = new Spindexer(hardwareMap);
|
|
||||||
|
|
||||||
servos = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
|
|
||||||
turret.manualSetTurret(0.4);
|
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot0 = null;
|
|
||||||
TrajectoryActionBuilder pickup1 = null;
|
|
||||||
TrajectoryActionBuilder shoot1 = null;
|
|
||||||
TrajectoryActionBuilder gatePickup = null;
|
|
||||||
TrajectoryActionBuilder shootCycle = null;
|
|
||||||
|
|
||||||
robot.spin1.setPosition(autoSpinStartPos);
|
|
||||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
robot.hood.setPosition(shoot0Hood);
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
robot.light.setPosition(0.28);
|
|
||||||
|
|
||||||
// ---- FIRST SHOT ----
|
|
||||||
x1 = rx1;
|
|
||||||
y1 = ry1;
|
|
||||||
h1 = rh1;
|
|
||||||
|
|
||||||
// ---- PICKUP PATH ----
|
|
||||||
x2a = rx2a;
|
|
||||||
y2a = ry2a;
|
|
||||||
h2a = rh2a;
|
|
||||||
t2a = rt2a;
|
|
||||||
x2b = rx2b;
|
|
||||||
y2b = ry2b;
|
|
||||||
h2b = rh2b;
|
|
||||||
t2b = rt2b;
|
|
||||||
x2c = rx2c;
|
|
||||||
y2c = ry2c;
|
|
||||||
h2c = rh2c;
|
|
||||||
t2c = rt2c;
|
|
||||||
|
|
||||||
xShoot = rShootX;
|
|
||||||
yShoot = rShootY;
|
|
||||||
hShoot = rShootH;
|
|
||||||
shoot1Tangent = rShoot1Tangent;
|
|
||||||
|
|
||||||
xGate = rXGate;
|
|
||||||
yGate = rYGate;
|
|
||||||
hGate = rHGate;
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.light.setPosition(0.6);
|
|
||||||
|
|
||||||
// ---- FIRST SHOT ----
|
|
||||||
x1 = bx1;
|
|
||||||
y1 = by1;
|
|
||||||
h1 = bh1;
|
|
||||||
|
|
||||||
// ---- PICKUP PATH ----
|
|
||||||
x2a = bx2a;
|
|
||||||
y2a = by2a;
|
|
||||||
h2a = bh2a;
|
|
||||||
t2a = bt2a;
|
|
||||||
x2b = bx2b;
|
|
||||||
y2b = by2b;
|
|
||||||
h2b = bh2b;
|
|
||||||
t2b = bt2b;
|
|
||||||
x2c = bx2c;
|
|
||||||
y2c = by2c;
|
|
||||||
h2c = bh2c;
|
|
||||||
t2c = bt2c;
|
|
||||||
|
|
||||||
xShoot = bShootX;
|
|
||||||
yShoot = bShootY;
|
|
||||||
hShoot = bShootH;
|
|
||||||
|
|
||||||
shoot1Tangent = bShoot1Tangent;
|
|
||||||
|
|
||||||
xGate = bXGate;
|
|
||||||
yGate = bYGate;
|
|
||||||
hGate = bHGate;
|
|
||||||
}
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
|
|
||||||
new TranslationalVelConstraint(pickup1Speed));
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
|
|
||||||
.setReversed(true)
|
|
||||||
.splineTo(new Vector2d(x2a, y2a), shoot1Tangent)
|
|
||||||
.splineToSplineHeading(new Pose2d(xShoot, yShoot, hShoot), shoot1Tangent);
|
|
||||||
|
|
||||||
gatePickup = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xGate, yGate), hGate);
|
|
||||||
|
|
||||||
shootCycle = drive.actionBuilder(new Pose2d(xGate, yGate, hGate))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
assert shoot0 != null;
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot0.build(),
|
|
||||||
manageFlywheel(
|
|
||||||
shoot0Vel,
|
|
||||||
shoot0Hood,
|
|
||||||
flywheel0Time,
|
|
||||||
x1,
|
|
||||||
0.501,
|
|
||||||
shoot0XTolerance,
|
|
||||||
0.501
|
|
||||||
)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
shootAll((int) shoot0Vel, shoot0Time, shoot0SpinSpeedIncrease)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup1.build(),
|
|
||||||
manageFlywheel(
|
|
||||||
shootAllVelocity,
|
|
||||||
shootAllHood,
|
|
||||||
pickup1Time,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
pickup1XTolerance,
|
|
||||||
pickup1YTolerance
|
|
||||||
),
|
|
||||||
intake(intake1Time),
|
|
||||||
detectObelisk(
|
|
||||||
obelisk1Time,
|
|
||||||
x2b,
|
|
||||||
y2c,
|
|
||||||
obelisk1XTolerance,
|
|
||||||
obelisk1YTolerance,
|
|
||||||
obeliskTurrPos
|
|
||||||
)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheel(
|
|
||||||
shootAllVelocity,
|
|
||||||
shootAllHood,
|
|
||||||
shoot1Time,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shoot1.build(),
|
|
||||||
prepareShootAll(shoot1Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageShooterAuto(
|
|
||||||
shootAllTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
gatePickup.build(),
|
|
||||||
manageShooterAuto(
|
|
||||||
gatePickupTime,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
pickup1XTolerance,
|
|
||||||
pickup1YTolerance
|
|
||||||
),
|
|
||||||
intake(gatePickupTime)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheelAuto(
|
|
||||||
shootCycleTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootCycle.build(),
|
|
||||||
prepareShootAll(shootCycleTime)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageShooterAuto(
|
|
||||||
shootAllTime,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
0.501
|
|
||||||
),
|
|
||||||
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,478 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.h1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.h2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.h2_b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.h3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.x1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.x2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.x2_b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.x3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.y1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.y2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.y2_b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.y3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
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.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.AprilTag;
|
||||||
|
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
|
||||||
|
@Autonomous (preselectTeleOp = "TeleopV1")
|
||||||
|
public class Blue extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTag aprilTag;
|
||||||
|
|
||||||
|
Shooter shooter;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public static double angle = 0.1;
|
||||||
|
|
||||||
|
Spindexer spindexer;
|
||||||
|
|
||||||
|
Transfer transfer;
|
||||||
|
|
||||||
|
public class shooterOn implements Action {
|
||||||
|
|
||||||
|
int ticker = 1;
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
if (ticker ==1){
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker ++;
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 0.2){
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - stamp < 0.4) {
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0,0,0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTag(robot, TELE);
|
||||||
|
|
||||||
|
shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
spindexer = new Spindexer(robot, TELE);
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setShooterMode("MANUAL");
|
||||||
|
|
||||||
|
shooter.sethoodPosition(0.53);
|
||||||
|
|
||||||
|
transfer = new Transfer(robot);
|
||||||
|
|
||||||
|
transfer.setTransferPosition(transferServo_out);
|
||||||
|
|
||||||
|
Intake intake = new Intake(robot);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj1 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj2 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.turnTo(Math.toRadians(-135))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2, -y2), -h2 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj3 = drive.actionBuilder(new Pose2d(x2, -y2, -h2))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj4 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2_b, -y2_b), -h2_b )
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x3, -y3), -h3 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj5 = drive.actionBuilder(new Pose2d(x3, -y3, -h3))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder traj6 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1-30), h1 );
|
||||||
|
|
||||||
|
while(opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()){
|
||||||
|
hoodDefault -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()){
|
||||||
|
hoodDefault += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
shooter.setTurretPosition(turret_blue);
|
||||||
|
|
||||||
|
aprilTag.initTelemetry();
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
TELE.addData("hood", hoodDefault);
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()){
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
traj1.build(),
|
||||||
|
new shooterOn()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
double stamp = getRuntime();
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.3);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
traj2.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
traj3.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.3);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
traj4.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
traj5.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.3);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
traj6.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addLine("finished");
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep (2000);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,431 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
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.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.AprilTag;
|
||||||
|
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;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous
|
||||||
|
public class Red extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTag aprilTag;
|
||||||
|
|
||||||
|
Shooter shooter;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public static double angle = 0.1;
|
||||||
|
|
||||||
|
Spindexer spindexer;
|
||||||
|
|
||||||
|
Transfer transfer;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0,0,0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTag(robot, TELE);
|
||||||
|
|
||||||
|
shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
spindexer = new Spindexer(robot, TELE);
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setShooterMode("MANUAL");
|
||||||
|
|
||||||
|
shooter.sethoodPosition(hoodDefault);
|
||||||
|
|
||||||
|
transfer = new Transfer(robot);
|
||||||
|
|
||||||
|
transfer.setTransferPosition(transferServo_out);
|
||||||
|
|
||||||
|
Intake intake = new Intake(robot);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.turnTo(Math.toRadians(135))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2, y2), h2 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(x2, y2, h2))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2_b, y2_b), h2_b )
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x3, y3), h3 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(x3, y3, h3))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1 );
|
||||||
|
|
||||||
|
|
||||||
|
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1+30), h1 );
|
||||||
|
|
||||||
|
while(opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()){
|
||||||
|
hoodDefault -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()){
|
||||||
|
hoodDefault += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
shooter.setTurretPosition(turret_red);
|
||||||
|
|
||||||
|
aprilTag.initTelemetry();
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()){
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
double stamp = getRuntime();
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.31);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
pickup1.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
shoot1.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.31);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
pickup2.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
shoot2.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
|
||||||
|
|
||||||
|
stamp = getRuntime();
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
while (getRuntime()-stamp<4.5) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.moveTurret(0.31);
|
||||||
|
|
||||||
|
double time = getRuntime()-stamp;
|
||||||
|
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 1) {
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 1.4) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 2.6) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (time < 3.0) {
|
||||||
|
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4.0) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
spindexer.outtake1();
|
||||||
|
|
||||||
|
} else if (time < 4.4) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.outtake3();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
park.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addLine("finished");
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep (2000);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -1,753 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
|
||||||
|
|
||||||
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.Disabled;
|
|
||||||
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;
|
|
||||||
|
|
||||||
@Disabled
|
|
||||||
@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.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-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.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,653 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
|
||||||
|
|
||||||
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.Disabled;
|
|
||||||
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;
|
|
||||||
@Disabled
|
|
||||||
@Config
|
|
||||||
@Autonomous
|
|
||||||
|
|
||||||
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.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-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.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,804 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
|
||||||
|
|
||||||
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.Disabled;
|
|
||||||
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;
|
|
||||||
@Disabled
|
|
||||||
@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.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)) {
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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.setPosition(-spinPow);
|
|
||||||
robot.spin2.setPosition(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.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-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.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
|
|
||||||
} else if (ticker % 60 < 30) {
|
|
||||||
robot.spin1.setPosition(-0.5);
|
|
||||||
robot.spin2.setPosition(0.5);
|
|
||||||
}
|
|
||||||
else if (ticker % 60 < 42) {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
robot.spin1.setPosition(0.5);
|
|
||||||
robot.spin2.setPosition(-0.5);
|
|
||||||
}
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
TELE.addData("Reverse?", reverse);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (getRuntime() - stamp > intakeTime) {
|
|
||||||
if (reverse) {
|
|
||||||
robot.spin1.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-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 = (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)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,298 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
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.utils.PositionalServoProgrammer.*;
|
||||||
|
|
||||||
|
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.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.AprilTag;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous
|
||||||
|
public class redDaniel extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTag aprilTag;
|
||||||
|
|
||||||
|
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
|
||||||
|
// TODO: change this velocity PID
|
||||||
|
public Action initShooter(int velocity){
|
||||||
|
return new Action(){
|
||||||
|
double velo = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket){
|
||||||
|
velo = -60 * ((((double) robot.shooter1.getCurrentPosition() / 2048) - initPos) / (getRuntime() - stamp));
|
||||||
|
stamp = getRuntime();
|
||||||
|
initPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
if (Math.abs(velocity - velo) > initTolerance) {
|
||||||
|
powPID = (double) velocity / maxVel;
|
||||||
|
ticker = getRuntime();
|
||||||
|
} else if (velocity - velTolerance > velo) {
|
||||||
|
powPID = powPID + 0.0001;
|
||||||
|
ticker = getRuntime();
|
||||||
|
} else if (velocity + velTolerance < velo) {
|
||||||
|
powPID = powPID - 0.0001;
|
||||||
|
ticker = getRuntime();
|
||||||
|
}
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower((powPID / 4) + 0.75);
|
||||||
|
|
||||||
|
return getRuntime() - ticker < 0.5;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public void Obelisk (){
|
||||||
|
// TODO: write the code to detect order
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(double spindexer){
|
||||||
|
return new Action() {
|
||||||
|
boolean transfer = false;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
robot.spin1.setPosition(spindexer);
|
||||||
|
robot.spin2.setPosition(1-spindexer);
|
||||||
|
if (scalar*((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01 && scalar*((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01){
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
transfer = true;
|
||||||
|
}
|
||||||
|
if (scalar*((robot.transferServoPos.getVoltage() - restPos) / 3.3) < transferServo_in + 0.01 && scalar*((robot.transferServoPos.getVoltage() - restPos) / 3.3) > transferServo_in - 0.01 && transfer){
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake (){
|
||||||
|
return new Action() {
|
||||||
|
double position = 0.0;
|
||||||
|
final double intakeTime = 4.0; // TODO: change this so it serves as a backup
|
||||||
|
final double stamp = getRuntime();
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if ((getRuntime() % 0.3) >0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1-position);
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
return !(robot.pin1.getState() && robot.pin3.getState() && robot.pin5.getState()) || getRuntime() - stamp > intakeTime;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect (){
|
||||||
|
return new Action() {
|
||||||
|
int t1 = 0;
|
||||||
|
int t2 = 0;
|
||||||
|
int t3 = 0;
|
||||||
|
int tP1 = 0;
|
||||||
|
int tP2 = 0;
|
||||||
|
int tP3 = 0;
|
||||||
|
final double stamp = getRuntime();
|
||||||
|
final double detectTime = 3.0;
|
||||||
|
double position = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if ((getRuntime() % 0.3) >0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1-position);
|
||||||
|
if (robot.pin1.getState()) {
|
||||||
|
t1 += 1;
|
||||||
|
if (robot.pin0.getState()){
|
||||||
|
tP1 += 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (robot.pin3.getState()) {
|
||||||
|
t2 += 1;
|
||||||
|
if (robot.pin0.getState()){
|
||||||
|
tP2 += 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (robot.pin5.getState()) {
|
||||||
|
t3 += 1;
|
||||||
|
if (robot.pin0.getState()){
|
||||||
|
tP3 += 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (t1 > 20){
|
||||||
|
if (tP1 > 20){
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (t2 > 20){
|
||||||
|
if (tP2 > 20){
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (t3 > 20){
|
||||||
|
if (tP3 > 20){
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return !(b1 + b2 + b3 >= 5) || (getRuntime() - stamp < detectTime);
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTag(robot, TELE);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.turnTo(Math.toRadians(h2))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2, y2), h2);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(x2, y2, h2))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2_b, y2_b), h2_b)
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(x3, y3), h3);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(x3, y3, h3))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x1, y1 + 30), h1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodDefault -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodDefault += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turret_red);
|
||||||
|
robot.turr2.setPosition(1 - turret_red);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
aprilTag.initTelemetry();
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodDefault);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
pickup1.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
shoot1.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
pickup2.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
shoot2.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
park.build()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addLine("finished");
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,11 +1,4 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Color {
|
public class Color {
|
||||||
public static boolean redAlliance = true;
|
|
||||||
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
|
|
||||||
|
|
||||||
public static double colorFilterAlpha = 0.15;
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
@@ -12,39 +13,17 @@ public class Poses {
|
|||||||
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
public static double x1 = 50, y1 = 0, h1 = 0;
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0.5, rh1 = Math.toRadians(0.1);
|
public static double x2 = 31, y2 = 32, h2 = Math.toRadians(140);
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
|
||||||
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140.1);
|
|
||||||
|
|
||||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
|
public static double x2_b = 58, y2_b = 42, h2_b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
|
||||||
public static double rx3b = 38, ry3b = 56, rh3b = Math.toRadians(140.1);
|
public static double x3 = 34, y3 = 58, h3 = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx4a = 72, ry4a = 65, rh4a = Math.toRadians(145);
|
public static Pose2d teleStart = new Pose2d(x1,-10,0);
|
||||||
public static double rx4b = 37, ry4b = 85, rh4b = Math.toRadians(145.1);
|
|
||||||
|
|
||||||
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 double rShootX = 40, rShootY = -7, rShootH = Math.toRadians(50);
|
|
||||||
public static double rxPrep = 45, ryPrep = 10, rhPrep = Math.toRadians(50);
|
|
||||||
|
|
||||||
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
|
|
||||||
public static double bxPrep = 50, byPrep = -10, bhPrep = Math.toRadians(140);
|
|
||||||
|
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,86 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Poses_LT_Indexed {
|
|
||||||
|
|
||||||
// ================= FIELD / GOAL =================
|
|
||||||
public static double goalHeight = 42; // inches
|
|
||||||
public static double turretHeight = 12;
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
|
||||||
|
|
||||||
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
|
||||||
|
|
||||||
// =================================================
|
|
||||||
// ================= RED ALLIANCE ==================
|
|
||||||
// =================================================
|
|
||||||
|
|
||||||
// -------- FIRST SHOT --------
|
|
||||||
public static double rx1 = 20, ry1 = 0, rh1 = 0;
|
|
||||||
|
|
||||||
// -------- PICKUP 1 --------
|
|
||||||
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI / 2);
|
|
||||||
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI / 2);
|
|
||||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI / 2);
|
|
||||||
|
|
||||||
// -------- OPEN GATE --------
|
|
||||||
public static double rXGate = 30, rYGate = 63, rHGate = Math.toRadians(179);
|
|
||||||
|
|
||||||
// -------- PICKUP 2 --------
|
|
||||||
public static double rx3 = 0, ry3 = 0, rh3 = 0, rt3 = 0;
|
|
||||||
|
|
||||||
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
|
||||||
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
|
|
||||||
|
|
||||||
// -------- PICKUP 3 --------
|
|
||||||
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 rx5a = 0, ry5a = 0, rh5a = 0;
|
|
||||||
public static double rx5b = 0, ry5b = 0, rh5b = 0;
|
|
||||||
|
|
||||||
// -------- SHOOT --------
|
|
||||||
public static double rShootX = 40, rShootY = 7, rShootH = Math.toRadians(140);
|
|
||||||
public static double rShoot1Tangent = Math.toRadians(0);
|
|
||||||
|
|
||||||
// -------- PARK --------
|
|
||||||
public static double rXPark = 0, rYPark = 0, rHPark = 0;
|
|
||||||
|
|
||||||
// =================================================
|
|
||||||
// ================= BLUE ALLIANCE =================
|
|
||||||
// =================================================
|
|
||||||
|
|
||||||
// -------- FIRST SHOT --------
|
|
||||||
public static double bx1 = 20, by1 = 0, bh1 = 0;
|
|
||||||
|
|
||||||
// -------- PICKUP 1 --------
|
|
||||||
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
|
|
||||||
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
|
|
||||||
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
|
|
||||||
|
|
||||||
// -------- OPEN GATE --------
|
|
||||||
public static double bXGate = 25, bYGate = 69, bHGate = Math.toRadians(165);
|
|
||||||
|
|
||||||
// -------- PICKUP 2 --------
|
|
||||||
public static double bx3 = 0, by3 = 0, bh3 = 0, bt3 = 0;
|
|
||||||
|
|
||||||
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
|
||||||
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
|
||||||
|
|
||||||
// -------- PICKUP 3 --------
|
|
||||||
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 bx5a = 0, by5a = 0, bh5a = 0;
|
|
||||||
public static double bx5b = 0, by5b = 0, bh5b = 0;
|
|
||||||
|
|
||||||
// -------- SHOOT --------
|
|
||||||
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
|
|
||||||
public static double bShoot1Tangent = Math.toRadians(0);
|
|
||||||
|
|
||||||
// -------- PARK --------
|
|
||||||
public static double bXPark = 0, bYPark = 0, bHPark = 0;
|
|
||||||
}
|
|
||||||
@@ -1,56 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Poses_V2 {
|
|
||||||
|
|
||||||
public static double goalHeight = 42; //in inches
|
|
||||||
|
|
||||||
public static double turretHeight = 12;
|
|
||||||
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
|
||||||
|
|
||||||
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0, rh1 = 0;
|
|
||||||
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI/2);
|
|
||||||
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI/2);
|
|
||||||
|
|
||||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI/2);
|
|
||||||
|
|
||||||
public static double rXGate = 30, rYGate = 63, rHGate = Math.toRadians(179);
|
|
||||||
|
|
||||||
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 = 20, by1 = 0, bh1 = 0;
|
|
||||||
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
|
|
||||||
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
|
|
||||||
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
|
|
||||||
|
|
||||||
public static double rShootX = 40, rShootY = 7, rShootH = Math.toRadians(140);
|
|
||||||
|
|
||||||
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
|
|
||||||
public static double bXGate = 25, bYGate = 69, bHGate = Math.toRadians(165);
|
|
||||||
|
|
||||||
|
|
||||||
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 double rShoot1Tangent = Math.toRadians(0);
|
|
||||||
public static double bShoot1Tangent = Math.toRadians(0);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,54 +1,34 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.05; //0.13;
|
public static double spindexer_intakePos1 = 0.665;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.24; //0.33;//0.5;
|
public static double spindexer_intakePos3 = 0.29;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.43; //0.53;//0.66;
|
public static double spindexer_intakePos2 = 0.99;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
|
public static double spindexer_outtakeBall3 = 0.845;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
public static double spindexer_outtakeBall2 = 0.48;
|
||||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
public static double spindexer_outtakeBall1 = 0.1;
|
||||||
public static double spinStartPos = spindexer_outtakeBall3 - 0.1;
|
|
||||||
|
|
||||||
public static double shootAllAutoSpinStartPos = 0.2;
|
|
||||||
public static double shootAllSpindexerSpeedIncrease = 0.02;
|
|
||||||
public static double shootAllTime = 1.8;
|
|
||||||
|
|
||||||
public static double transferServo_out = 0.15;
|
public static double transferServo_out = 0.15;
|
||||||
|
|
||||||
public static double transferServo_in = 0.38;
|
public static double transferServo_in = 0.38;
|
||||||
|
|
||||||
public static double turret_range = 0.9;
|
public static double hoodDefault = 0.35;
|
||||||
|
|
||||||
public static double hoodDefault = 0.6;
|
public static double hoodHigh = 0.21;
|
||||||
|
|
||||||
public static double hoodAuto = 0.27;
|
public static double hoodLow = 1.0;
|
||||||
|
|
||||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
public static double turret_red = 0.43;
|
||||||
|
public static double turret_blue = 0.4;
|
||||||
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;
|
|
||||||
|
|
||||||
public static double turrMin = 0.2;
|
|
||||||
public static double turrMax = 0.8;
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,15 +12,5 @@ public class ShooterVars {
|
|||||||
|
|
||||||
public static int initTolerance = 1000;
|
public static int initTolerance = 1000;
|
||||||
|
|
||||||
public static int maxVel = 4500;
|
public static int maxVel = 4000;
|
||||||
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
|
|
||||||
|
|
||||||
public static Types.Motif currentMotif = Types.Motif.NONE;
|
|
||||||
}
|
|
||||||
|
|||||||
@@ -1,10 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
public class Types {
|
|
||||||
public enum Motif {
|
|
||||||
NONE,
|
|
||||||
GPP, // Green, Purple, Purple
|
|
||||||
PGP, // Purple, Green, Purple
|
|
||||||
PPG // Purple, Purple, Green
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -73,13 +73,13 @@ public final class MecanumDrive {
|
|||||||
public double kA = 0.000046;
|
public double kA = 0.000046;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// path profile parameters (in inches)
|
||||||
public double maxWheelVel = 180;
|
public double maxWheelVel = 120;
|
||||||
public double minProfileAccel = -40;
|
public double minProfileAccel = -30;
|
||||||
public double maxProfileAccel = 180;
|
public double maxProfileAccel = 120;
|
||||||
|
|
||||||
// turn profile parameters (in radians)
|
// turn profile parameters (in radians)
|
||||||
public double maxAngVel = 4* Math.PI; // shared with path
|
public double maxAngVel = 2* Math.PI; // shared with path
|
||||||
public double maxAngAccel = 4* Math.PI;
|
public double maxAngAccel = 2* Math.PI;
|
||||||
|
|
||||||
// path controller gains
|
// path controller gains
|
||||||
public double axialGain = 4;
|
public double axialGain = 4;
|
||||||
@@ -454,14 +454,14 @@ public final class MecanumDrive {
|
|||||||
public PoseVelocity2d updatePoseEstimate() {
|
public PoseVelocity2d updatePoseEstimate() {
|
||||||
PoseVelocity2d vel = localizer.update();
|
PoseVelocity2d vel = localizer.update();
|
||||||
poseHistory.add(localizer.getPose());
|
poseHistory.add(localizer.getPose());
|
||||||
|
|
||||||
while (poseHistory.size() > 100) {
|
while (poseHistory.size() > 100) {
|
||||||
poseHistory.removeFirst();
|
poseHistory.removeFirst();
|
||||||
}
|
}
|
||||||
|
|
||||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||||
|
|
||||||
|
|
||||||
return vel;
|
return vel;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1,130 +1,147 @@
|
|||||||
## TeamCode Module
|
# Team FTC Git Workflow Guide
|
||||||
|
|
||||||
Welcome!
|
|
||||||
|
|
||||||
This module, TeamCode, is the place where you will write/paste the code for your team's
|
## 1. Cloning the Repository
|
||||||
robot controller App. This module is currently empty (a clean slate) but the
|
|
||||||
process for adding OpModes is straightforward.
|
|
||||||
|
|
||||||
## Creating your own OpModes
|
1. Open a terminal (or the terminal inside Android Studio).
|
||||||
|
2. Navigate to the folder where you want to keep the project.
|
||||||
|
3. Run:
|
||||||
|
|
||||||
The easiest way to create your own OpMode is to copy a Sample OpMode and make it your own.
|
```bash
|
||||||
|
git clone https://github.com/KeshavAnandCode/DecodeFTCMain.git
|
||||||
|
cd DecodeFTCMain
|
||||||
|
```
|
||||||
|
|
||||||
Sample opmodes exist in the FtcRobotController module.
|
4. Verify your remotes:
|
||||||
To locate these samples, find the FtcRobotController module in the "Project/Android" tab.
|
|
||||||
|
|
||||||
Expand the following tree elements:
|
```bash
|
||||||
FtcRobotController/java/org.firstinspires.ftc.robotcontroller/external/samples
|
git remote -v
|
||||||
|
```
|
||||||
|
|
||||||
### Naming of Samples
|
You should see:
|
||||||
|
```
|
||||||
|
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.
|
|
||||||
|
|
||||||
These conventions are described (in detail) in the sample_conventions.md file in this folder.
|
## 2. Keeping `master` Clean
|
||||||
|
|
||||||
To summarize: A range of different samples classes will reside in the java/external/samples.
|
- `master` should only contain clean, tested code.
|
||||||
The class names will follow a naming convention which indicates the purpose of each class.
|
- Nobody should ever code directly on `master`.
|
||||||
The prefix of the name will be one of the following:
|
- To stay up to date:
|
||||||
|
|
||||||
Basic: This is a minimally functional OpMode used to illustrate the skeleton/structure
|
```bash
|
||||||
of a particular style of OpMode. These are bare bones examples.
|
git checkout master
|
||||||
|
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.
|
|
||||||
|
|
||||||
Robot: This is a Sample OpMode that assumes a simple two-motor (differential) drive base.
|
## 3. Creating a Feature Branch
|
||||||
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.
|
|
||||||
|
|
||||||
Concept: This is a sample OpMode that illustrates performing a specific function or concept.
|
Whenever you start a new task (feature, fix, experiment):
|
||||||
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.
|
|
||||||
|
|
||||||
After the prefix, other conventions will apply:
|
1. Update `master` (see above).
|
||||||
|
2. Create a new branch from `master`:
|
||||||
|
|
||||||
* Sensor class names are constructed as: Sensor - Company - Type
|
```bash
|
||||||
* Robot class names are constructed as: Robot - Mode - Action - OpModetype
|
git checkout master
|
||||||
* Concept class names are constructed as: Concept - Topic - OpModetype
|
git pull origin master
|
||||||
|
git checkout -b feature/short-description
|
||||||
|
```
|
||||||
|
|
||||||
Once you are familiar with the range of samples available, you can choose one to be the
|
### Branch Naming Standard
|
||||||
basis for your own robot. In all cases, the desired sample(s) needs to be copied into
|
|
||||||
your TeamCode module to be used.
|
|
||||||
|
|
||||||
This is done inside Android Studio directly, using the following steps:
|
Branches **must** follow the format:
|
||||||
|
|
||||||
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:
|
|
||||||
|
|
||||||
```
|
```
|
||||||
@TeleOp(name="Template: Linear OpMode", group="Linear Opmode")
|
<type>/<short-description>
|
||||||
@Disabled
|
|
||||||
```
|
```
|
||||||
|
|
||||||
The name that will appear on the driver station's "opmode list" is defined by the code:
|
Where `<type>` is one of:
|
||||||
``name="Template: Linear OpMode"``
|
- `feature/` → new functionality
|
||||||
You can change what appears between the quotes to better describe your opmode.
|
- `fix/` → bug fixes
|
||||||
The "group=" portion of the code can be used to help organize your list of OpModes.
|
- `experiment/` → prototypes or tests
|
||||||
|
- `docs/` → documentation updates
|
||||||
|
- `chore/` → maintenance or cleanup
|
||||||
|
|
||||||
As shown, the current OpMode will NOT appear on the driver station's OpMode list because of the
|
Examples:
|
||||||
``@Disabled`` annotation which has been included.
|
- `feature/autonomous-path`
|
||||||
This line can simply be deleted , or commented out, to make the OpMode visible.
|
- `fix/motor-init`
|
||||||
|
- `experiment/vision-test`
|
||||||
|
- `docs/setup-instructions`
|
||||||
|
- `chore/gradle-update`
|
||||||
|
|
||||||
## ADVANCED Multi-Team App management: Cloning the TeamCode Module
|
**Rules for names:**
|
||||||
|
- 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.
|
|
||||||
|
|
||||||
In this situation, you might wish to clone the TeamCode module, once for each of these teams.
|
## 4. Working on Your Branch
|
||||||
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).
|
|
||||||
|
|
||||||
Selective Team phones can then be programmed by selecting the desired Module from the pulldown list
|
- Make changes in Android Studio.
|
||||||
prior to clicking to the green Run arrow.
|
- Stage and commit your changes:
|
||||||
|
|
||||||
Warning: This is not for the inexperienced Software developer.
|
```bash
|
||||||
You will need to be comfortable with File manipulations and managing Android Studio Modules.
|
git add .
|
||||||
These changes are performed OUTSIDE of Android Studios, so close Android Studios before you do this.
|
git commit -m "short message about what changed"
|
||||||
|
```
|
||||||
|
|
||||||
Also.. Make a full project backup before you start this :)
|
- Push your branch to GitHub:
|
||||||
|
|
||||||
To clone TeamCode, do the following:
|
```bash
|
||||||
|
git push origin feature/short-description
|
||||||
|
```
|
||||||
|
|
||||||
Note: Some names start with "Team" and others start with "team". This is intentional.
|
---
|
||||||
|
|
||||||
1) Using your operating system file management tools, copy the whole "TeamCode"
|
## 5. Sharing Your Work
|
||||||
folder to a sibling folder with a corresponding new name, eg: "Team0417".
|
|
||||||
|
|
||||||
2) In the new Team0417 folder, delete the TeamCode.iml file.
|
- Once your branch is ready:
|
||||||
|
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".
|
|
||||||
|
|
||||||
4) In the new Team0417/src/main folder, edit the "AndroidManifest.xml" file, change the line that
|
## 6. Branching Rules
|
||||||
contains
|
|
||||||
package="org.firstinspires.ftc.teamcode"
|
|
||||||
to be
|
|
||||||
package="org.firstinspires.ftc.team0417"
|
|
||||||
|
|
||||||
5) Add: include ':Team0417' to the "/settings.gradle" file.
|
**Do:**
|
||||||
|
- Always branch from `master`.
|
||||||
|
- Follow the naming standard exactly.
|
||||||
|
- Keep branches small and focused.
|
||||||
|
- Delete branches after they’re merged.
|
||||||
|
|
||||||
6) Open up Android Studios and clean out any old files by using the menu to "Build/Clean Project""
|
**Don’t:**
|
||||||
|
- 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,238 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Subsystem;
|
||||||
|
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.Collections;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
public class AprilTag implements Subsystem {
|
||||||
|
|
||||||
|
private AprilTagProcessor aprilTag;
|
||||||
|
private VisionPortal visionPortal;
|
||||||
|
|
||||||
|
private MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
private boolean teleOn = false;
|
||||||
|
|
||||||
|
private int detections = 0;
|
||||||
|
|
||||||
|
List<AprilTagDetection> currentDetections;
|
||||||
|
|
||||||
|
ArrayList<ArrayList<Double>> Data = new ArrayList<>();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public AprilTag(Robot robot, MultipleTelemetry tele) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
this.aprilTag = robot.aprilTagProcessor;
|
||||||
|
|
||||||
|
|
||||||
|
this.TELE = tele;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
currentDetections = aprilTag.getDetections();
|
||||||
|
|
||||||
|
UpdateData();
|
||||||
|
|
||||||
|
if(teleOn){
|
||||||
|
tagTELE();
|
||||||
|
initTelemetry();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void initTelemetry (){
|
||||||
|
|
||||||
|
TELE.addData("Camera Preview", "Check Driver Station for stream");
|
||||||
|
TELE.addData("Status", "Initialized - Press START");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void tagTELE () {
|
||||||
|
|
||||||
|
TELE.addData("# AprilTags Detected", detections);
|
||||||
|
|
||||||
|
// Display info for each detected tag
|
||||||
|
for (ArrayList<Double> detection : Data) {
|
||||||
|
if (detection.get(0) ==1) {
|
||||||
|
// Known AprilTag with metadata
|
||||||
|
TELE.addLine(String.format("\n==== (ID %d) %s ====",
|
||||||
|
detection.get(1).intValue(), ""));
|
||||||
|
|
||||||
|
TELE.addLine(String.format("XYZ: %6.1f %6.1f %6.1f (inch)",
|
||||||
|
detection.get(2),
|
||||||
|
detection.get(3),
|
||||||
|
detection.get(4)));
|
||||||
|
|
||||||
|
TELE.addData("Distance", getDistance(detection.get(1).intValue()));
|
||||||
|
|
||||||
|
TELE.addLine(String.format("PRY: %6.1f %6.1f %6.1f (deg)",
|
||||||
|
detection.get(5),
|
||||||
|
detection.get(6),
|
||||||
|
detection.get(7)));
|
||||||
|
|
||||||
|
TELE.addLine(String.format("RBE: %6.1f %6.1f %6.1f (inch, deg, deg)",
|
||||||
|
detection.get(8),
|
||||||
|
detection.get(9),
|
||||||
|
detection.get(10)));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public void turnTelemetryOn(boolean bool) {
|
||||||
|
|
||||||
|
teleOn = bool;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public void UpdateData () {
|
||||||
|
|
||||||
|
Data.clear(); // <--- THIS FIXES YOUR ISSUE
|
||||||
|
|
||||||
|
|
||||||
|
detections = currentDetections.size();
|
||||||
|
|
||||||
|
|
||||||
|
for (AprilTagDetection detection : currentDetections) {
|
||||||
|
|
||||||
|
ArrayList<Double> detectionData = new ArrayList<Double>();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (detection.metadata != null) {
|
||||||
|
|
||||||
|
detectionData.add(1.0);
|
||||||
|
// Known AprilTag with metadata
|
||||||
|
|
||||||
|
detectionData.add( (double) detection.id);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
detectionData.add(detection.ftcPose.x);
|
||||||
|
detectionData.add(detection.ftcPose.y);
|
||||||
|
detectionData.add(detection.ftcPose.z);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
detectionData.add(detection.ftcPose.pitch);
|
||||||
|
detectionData.add(detection.ftcPose.roll);
|
||||||
|
detectionData.add(detection.ftcPose.yaw);
|
||||||
|
|
||||||
|
detectionData.add(detection.ftcPose.range);
|
||||||
|
detectionData.add(detection.ftcPose.bearing);
|
||||||
|
detectionData.add(detection.ftcPose.elevation);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
detectionData.add(0, 0.0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Data.add(detectionData);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public int getDetectionCount() {
|
||||||
|
|
||||||
|
return detections;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isDetected (int id){
|
||||||
|
return (!filterID(Data, (double) id ).isEmpty());
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public double getDistance(int id) {
|
||||||
|
ArrayList<Double> d = filterID(Data, (double) id);
|
||||||
|
if (d.size() >= 5) {
|
||||||
|
double x = d.get(2);
|
||||||
|
double y = d.get(3);
|
||||||
|
double z = d.get(4);
|
||||||
|
return Math.sqrt(x*x + y*y + z*z);
|
||||||
|
}
|
||||||
|
return -1; // tag not found
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns the position as [x, y, z]
|
||||||
|
public List<Double> getPosition(int id) {
|
||||||
|
ArrayList<Double> d = filterID(Data, (double) id);
|
||||||
|
if (d.size() >= 5) {
|
||||||
|
List<Double> pos = new ArrayList<>();
|
||||||
|
pos.add(d.get(2));
|
||||||
|
pos.add(d.get(3));
|
||||||
|
pos.add(d.get(4));
|
||||||
|
return pos;
|
||||||
|
}
|
||||||
|
return Collections.emptyList();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns orientation as [pitch, roll, yaw]
|
||||||
|
public List<Double> getOrientation(int id) {
|
||||||
|
ArrayList<Double> d = filterID(Data, (double) id);
|
||||||
|
if (d.size() >= 8) {
|
||||||
|
List<Double> ori = new ArrayList<>();
|
||||||
|
ori.add(d.get(5));
|
||||||
|
ori.add(d.get(6));
|
||||||
|
ori.add(d.get(7));
|
||||||
|
return ori;
|
||||||
|
}
|
||||||
|
return Collections.emptyList();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns range, bearing, elevation as [range, bearing, elevation]
|
||||||
|
public List<Double> getRBE(int id) {
|
||||||
|
ArrayList<Double> d = filterID(Data, (double) id);
|
||||||
|
if (d.size() >= 11) {
|
||||||
|
List<Double> rbe = new ArrayList<>();
|
||||||
|
rbe.add(d.get(8));
|
||||||
|
rbe.add(d.get(9));
|
||||||
|
rbe.add(d.get(10));
|
||||||
|
return rbe;
|
||||||
|
}
|
||||||
|
return Collections.emptyList();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns full raw data for debugging or custom processing
|
||||||
|
public ArrayList<Double> getRawData(int id) {
|
||||||
|
return filterID(Data, (double) id);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static ArrayList<Double> filterID(ArrayList<ArrayList<Double>> data, double x) {
|
||||||
|
for (ArrayList<Double> innerList : data) {
|
||||||
|
// Ensure it has a second element
|
||||||
|
if (innerList.size() > 1 && Math.abs(innerList.get(1) - x) < 1e-9) {
|
||||||
|
return innerList; // Return the first match
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Return an empty ArrayList if no match found
|
||||||
|
return new ArrayList<>();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,99 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Subsystem;
|
||||||
|
|
||||||
|
import java.util.Objects;
|
||||||
|
|
||||||
|
public class Drivetrain implements Subsystem {
|
||||||
|
|
||||||
|
private final GamepadEx gamepad;
|
||||||
|
|
||||||
|
public MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
private String Mode = "Default";
|
||||||
|
|
||||||
|
private final DcMotorEx fl;
|
||||||
|
|
||||||
|
private final DcMotorEx fr;
|
||||||
|
private final DcMotorEx bl;
|
||||||
|
private final DcMotorEx br;
|
||||||
|
|
||||||
|
private double defaultSpeed = 0.7;
|
||||||
|
|
||||||
|
private double slowSpeed = 0.3;
|
||||||
|
public Drivetrain(Robot robot, MultipleTelemetry tele, GamepadEx gamepad1){
|
||||||
|
|
||||||
|
this.fl = robot.frontLeft;
|
||||||
|
this.fr = robot.frontRight;
|
||||||
|
this.br = robot.backRight;
|
||||||
|
this.bl = robot.backLeft;
|
||||||
|
|
||||||
|
this.gamepad = gamepad1;
|
||||||
|
|
||||||
|
this.TELE = tele;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setMode (String mode){
|
||||||
|
this.Mode = mode;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setDefaultSpeed (double speed){
|
||||||
|
this.defaultSpeed = speed;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setSlowSpeed (double speed){
|
||||||
|
this.slowSpeed = speed;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void RobotCentric(double fwd, double strafe, double turn, double turbo){
|
||||||
|
|
||||||
|
double y = -fwd; // Remember, Y stick value is reversed
|
||||||
|
double x = strafe * 1.1; // Counteract imperfect strafing
|
||||||
|
double rx = turn;
|
||||||
|
|
||||||
|
// Denominator is the largest motor power (absolute value) or 1
|
||||||
|
// This ensures all the powers maintain the same ratio,
|
||||||
|
// but only if at least one is out of the range [-1, 1]
|
||||||
|
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;
|
||||||
|
|
||||||
|
fl.setPower(frontLeftPower*turbo);
|
||||||
|
bl.setPower(backLeftPower*turbo);
|
||||||
|
fr.setPower(frontRightPower*turbo);
|
||||||
|
br.setPower(backRightPower*turbo);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
if (Objects.equals(Mode, "Default")) {
|
||||||
|
|
||||||
|
RobotCentric(
|
||||||
|
gamepad.getRightY(),
|
||||||
|
gamepad.getRightX(),
|
||||||
|
gamepad.getLeftX(),
|
||||||
|
(gamepad.getTrigger(
|
||||||
|
GamepadKeys.Trigger.RIGHT_TRIGGER) * (1-defaultSpeed)
|
||||||
|
- gamepad.getTrigger(GamepadKeys.Trigger.LEFT_TRIGGER) * slowSpeed
|
||||||
|
+ defaultSpeed
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,80 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||||
|
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
public class Intake implements Subsystem {
|
||||||
|
|
||||||
|
private GamepadEx gamepad;
|
||||||
|
|
||||||
|
public MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
|
||||||
|
private DcMotorEx intake;
|
||||||
|
|
||||||
|
private double intakePower = 1.0;
|
||||||
|
|
||||||
|
private int intakeState = 0;
|
||||||
|
|
||||||
|
|
||||||
|
public Intake (Robot robot){
|
||||||
|
|
||||||
|
|
||||||
|
this.intake = robot.intake;
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public int getIntakeState() {
|
||||||
|
return intakeState;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void toggle(){
|
||||||
|
if (intakeState !=0){
|
||||||
|
intakeState = 0;
|
||||||
|
} else {
|
||||||
|
intakeState = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intakeMinPower(){
|
||||||
|
intakeState = 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intake(){
|
||||||
|
intakeState =1;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void reverse(){
|
||||||
|
intakeState =-1;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public void stop(){
|
||||||
|
intakeState =0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
if (intakeState == 1){
|
||||||
|
intake.setPower(intakePower);
|
||||||
|
} else if (intakeState == -1){
|
||||||
|
intake.setPower(-intakePower);
|
||||||
|
} else if (intakeState == 2){
|
||||||
|
intake.setPower(intakePower);
|
||||||
|
}else {
|
||||||
|
intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,248 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.ShooterTest.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDController;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.PIDCoefficients;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.Poses;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
import java.util.Objects;
|
||||||
|
|
||||||
|
public class Shooter implements Subsystem {
|
||||||
|
private final DcMotorEx fly1;
|
||||||
|
private final DcMotorEx fly2;
|
||||||
|
|
||||||
|
private final DcMotorEx encoder;
|
||||||
|
private final Servo hoodServo;
|
||||||
|
|
||||||
|
private final Servo turret1;
|
||||||
|
|
||||||
|
private final Servo turret2;
|
||||||
|
|
||||||
|
private final MultipleTelemetry telemetry;
|
||||||
|
|
||||||
|
private boolean telemetryOn = false;
|
||||||
|
|
||||||
|
private double manualPower = 0.0;
|
||||||
|
private double hoodPos = 0.0;
|
||||||
|
|
||||||
|
private double turretPos = 0.0;
|
||||||
|
private double velocity = 0.0;
|
||||||
|
private double posPower = 0.0;
|
||||||
|
|
||||||
|
public double velo = 0.0;
|
||||||
|
|
||||||
|
private int targetPosition = 0;
|
||||||
|
|
||||||
|
public double powPID = 1.0;
|
||||||
|
|
||||||
|
private double p = 0.0003, i = 0, d = 0.00001, f=0;
|
||||||
|
|
||||||
|
private PIDFController controller;
|
||||||
|
private double pow = 0.0;
|
||||||
|
|
||||||
|
private String shooterMode = "AUTO";
|
||||||
|
|
||||||
|
private String turretMode = "AUTO";
|
||||||
|
|
||||||
|
public Shooter(Robot robot, MultipleTelemetry TELE) {
|
||||||
|
this.fly1 = robot.shooter1;
|
||||||
|
this.fly2 = robot.shooter2;
|
||||||
|
this.telemetry = TELE;
|
||||||
|
this.hoodServo = robot.hood;
|
||||||
|
|
||||||
|
// Reset encoders
|
||||||
|
fly1.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
|
fly2.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
|
|
||||||
|
fly1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
fly1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
|
controller = new PIDFController(p, i, d, f);
|
||||||
|
|
||||||
|
controller.setPIDF(p, i, d, f);
|
||||||
|
|
||||||
|
this.turret1 = robot.turr1;
|
||||||
|
|
||||||
|
this.turret2 = robot.turr2;
|
||||||
|
|
||||||
|
this.encoder = robot.shooterEncoder;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public double gethoodPosition() {
|
||||||
|
return (hoodServo.getPosition());
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sethoodPosition(double pos) { hoodPos = pos; }
|
||||||
|
|
||||||
|
public double getTurretPosition() {
|
||||||
|
return ((turret1.getPosition() + (1 - turret2.getPosition())) / 2);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTurretPosition(double pos) { turretPos = pos; }
|
||||||
|
|
||||||
|
public double getVelocity(double vel) {
|
||||||
|
return vel;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setVelocity(double vel) { velocity = vel; }
|
||||||
|
|
||||||
|
public void setPosPower(double power) { posPower = power; }
|
||||||
|
|
||||||
|
public void setTargetPosition(int pos) {
|
||||||
|
targetPosition = pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTolerance(int tolerance) {
|
||||||
|
controller.setTolerance(tolerance);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setControllerCoefficients(double kp, double ki, double kd, double kf) {
|
||||||
|
p = kp;
|
||||||
|
i = ki;
|
||||||
|
d = kd;
|
||||||
|
f = kf;
|
||||||
|
controller.setPIDF(p, i, d, f);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public PIDCoefficients getControllerCoefficients() {
|
||||||
|
|
||||||
|
return new PIDCoefficients(p, i, d);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setManualPower(double power) { manualPower = power; }
|
||||||
|
|
||||||
|
public String getShooterMode() { return shooterMode; }
|
||||||
|
|
||||||
|
public String getTurretMode() { return turretMode; }
|
||||||
|
|
||||||
|
public double getECPRPosition() {
|
||||||
|
return fly1.getCurrentPosition() / (2 * ecpr);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getMCPRPosition() {
|
||||||
|
return (double) fly1.getCurrentPosition() / 4;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setShooterMode(String mode) { shooterMode = mode; }
|
||||||
|
|
||||||
|
public void setTurretMode(String mode) { turretMode = mode; }
|
||||||
|
|
||||||
|
public double trackGoal(Pose2d robotPose, Pose2d goalPose, double offset) {
|
||||||
|
|
||||||
|
fly1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
fly2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
|
Pose2d deltaPose = new Pose2d(
|
||||||
|
goalPose.position.x - robotPose.position.x,
|
||||||
|
goalPose.position.y - robotPose.position.y,
|
||||||
|
goalPose.heading.toDouble() - (robotPose.heading.toDouble())
|
||||||
|
);
|
||||||
|
|
||||||
|
double distance = Math.sqrt(
|
||||||
|
deltaPose.position.x * deltaPose.position.x
|
||||||
|
+ deltaPose.position.y * deltaPose.position.y
|
||||||
|
+ Poses.relativeGoalHeight * Poses.relativeGoalHeight
|
||||||
|
);
|
||||||
|
|
||||||
|
telemetry.addData("dst", distance);
|
||||||
|
|
||||||
|
double shooterPow = getPowerByDist(distance);
|
||||||
|
|
||||||
|
double hoodAngle = getAngleByDist(distance);
|
||||||
|
|
||||||
|
// hoodServo.setPosition(hoodAngle);
|
||||||
|
|
||||||
|
moveTurret(getTurretPosByDeltaPose(deltaPose, offset));
|
||||||
|
|
||||||
|
return distance;
|
||||||
|
|
||||||
|
//0.9974 * 355
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getTurretPosByDeltaPose(Pose2d dPose, double offset) {
|
||||||
|
|
||||||
|
double deltaAngle = Math.toDegrees(dPose.heading.toDouble());
|
||||||
|
|
||||||
|
double aTanAngle = Math.toDegrees(Math.atan(dPose.position.y / dPose.position.x));
|
||||||
|
|
||||||
|
telemetry.addData("deltaAngle", deltaAngle);
|
||||||
|
|
||||||
|
if (deltaAngle > 90) {
|
||||||
|
deltaAngle -= 360;
|
||||||
|
}
|
||||||
|
|
||||||
|
// deltaAngle += aTanAngle;
|
||||||
|
|
||||||
|
deltaAngle /= (335);
|
||||||
|
|
||||||
|
telemetry.addData("dAngle", deltaAngle);
|
||||||
|
|
||||||
|
telemetry.addData("AtanAngle", aTanAngle);
|
||||||
|
|
||||||
|
return ((0.30 - deltaAngle) + offset);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//62, 0.44
|
||||||
|
|
||||||
|
//56.5, 0.5
|
||||||
|
|
||||||
|
public double getPowerByDist(double dist) {
|
||||||
|
|
||||||
|
//TODO: ADD LOGIC
|
||||||
|
return dist;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getAngleByDist(double dist) {
|
||||||
|
|
||||||
|
double newDist = dist - 56.5;
|
||||||
|
|
||||||
|
double pos = newDist * ((0.44 - 0.5) / (62 - 56.5)) + 0.46;
|
||||||
|
|
||||||
|
return pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTelemetryOn(boolean state) { telemetryOn = state; }
|
||||||
|
|
||||||
|
public void moveTurret(double pos) {
|
||||||
|
turret1.setPosition(pos);
|
||||||
|
turret2.setPosition(1 - pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getpowPID() {
|
||||||
|
return powPID;
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
if (Objects.equals(shooterMode, "MANUAL")) {
|
||||||
|
fly1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
fly2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
fly1.setPower(manualPower);
|
||||||
|
fly2.setPower(manualPower);
|
||||||
|
} else if (Objects.equals(shooterMode, "VEL")) {
|
||||||
|
powPID = velocity;
|
||||||
|
|
||||||
|
fly1.setPower(powPID);
|
||||||
|
fly2.setPower(powPID);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,255 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||||
|
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
public class Spindexer implements Subsystem{
|
||||||
|
|
||||||
|
private Servo s1;
|
||||||
|
private Servo s2;
|
||||||
|
|
||||||
|
private DigitalChannel p0;
|
||||||
|
|
||||||
|
private DigitalChannel p1;
|
||||||
|
private DigitalChannel p2;
|
||||||
|
private DigitalChannel p3;
|
||||||
|
private DigitalChannel p4;
|
||||||
|
|
||||||
|
private DigitalChannel p5;
|
||||||
|
|
||||||
|
private AnalogInput input;
|
||||||
|
|
||||||
|
private AnalogInput input2;
|
||||||
|
|
||||||
|
|
||||||
|
private MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
private double position = 0.501;
|
||||||
|
|
||||||
|
private boolean telemetryOn = false;
|
||||||
|
|
||||||
|
private boolean ball0 = false;
|
||||||
|
|
||||||
|
private boolean ball1 = false;
|
||||||
|
|
||||||
|
private boolean ball2 = false;
|
||||||
|
|
||||||
|
private boolean green0 = false;
|
||||||
|
|
||||||
|
private boolean green1 = false;
|
||||||
|
|
||||||
|
private boolean green2 = false;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public Spindexer (Robot robot, MultipleTelemetry tele){
|
||||||
|
|
||||||
|
this.s1 = robot.spin1;
|
||||||
|
this.s2 = robot.spin2;
|
||||||
|
|
||||||
|
this.p0 = robot.pin0;
|
||||||
|
this.p1 = robot.pin1;
|
||||||
|
this.p2 = robot.pin2;
|
||||||
|
this.p3 = robot.pin3;
|
||||||
|
this.p4 = robot.pin4;
|
||||||
|
this.p5 = robot.pin5;
|
||||||
|
|
||||||
|
this.input = robot.analogInput;
|
||||||
|
|
||||||
|
this.input2 = robot.analogInput2;
|
||||||
|
|
||||||
|
this.TELE = tele;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTelemetryOn(boolean state){
|
||||||
|
telemetryOn = state;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void colorSensorTelemetry() {
|
||||||
|
|
||||||
|
|
||||||
|
TELE.addData("ball0", ball0);
|
||||||
|
TELE.addData("ball1", ball1);
|
||||||
|
TELE.addData("ball2", ball2);
|
||||||
|
TELE.addData("green0", green0);
|
||||||
|
TELE.addData("green1", green1);
|
||||||
|
TELE.addData("green2", green2);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void checkForBalls() {
|
||||||
|
|
||||||
|
if (p0.getState()){
|
||||||
|
ball0 = true;
|
||||||
|
green0 = p1.getState();
|
||||||
|
} else {
|
||||||
|
ball0 = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (p2.getState()){
|
||||||
|
ball1 = true;
|
||||||
|
green1 = p3.getState();
|
||||||
|
} else {
|
||||||
|
ball1 = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (p4.getState()){
|
||||||
|
ball2 = true;
|
||||||
|
green2 = p5.getState();
|
||||||
|
} else {
|
||||||
|
ball2 = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setPosition (double pos) {
|
||||||
|
position = pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intake () {
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intakeShake(double runtime) {
|
||||||
|
if ((runtime % 0.25) >0.125) {
|
||||||
|
position = spindexer_intakePos1 + 0.04;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.04;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void outtake3Shake(double runtime) {
|
||||||
|
if ((runtime % 0.25) >0.125) {
|
||||||
|
position = spindexer_outtakeBall3 + 0.04;
|
||||||
|
} else {
|
||||||
|
position = spindexer_outtakeBall3 - 0.04;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public void outtake3 () {
|
||||||
|
position = spindexer_outtakeBall3;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void outtake2 () {
|
||||||
|
position = spindexer_outtakeBall2;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void outtake1 () {
|
||||||
|
position = spindexer_outtakeBall1;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public int outtakeGreen(int secLast, int Last) {
|
||||||
|
if (green2 && (secLast!=3) && (Last!=3)) {
|
||||||
|
outtake3();
|
||||||
|
return 3;
|
||||||
|
} else if (green1 && (secLast!=2) && (Last!=2)){
|
||||||
|
outtake2();
|
||||||
|
return 2;
|
||||||
|
} else if (green0 && (secLast!=1) && (Last!=1)) {
|
||||||
|
outtake1();
|
||||||
|
return 1;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
if (secLast!=1 && Last!= 1){
|
||||||
|
outtake1();
|
||||||
|
return 1;
|
||||||
|
} else if (secLast!=2 && Last!=2){
|
||||||
|
outtake2();
|
||||||
|
return 2;
|
||||||
|
} else {
|
||||||
|
outtake3();
|
||||||
|
return 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public void outtakeGreenFs() {
|
||||||
|
if (green0 && ball0) {
|
||||||
|
outtake1();
|
||||||
|
} else if (green1 && ball1){
|
||||||
|
outtake2();
|
||||||
|
} else if (green2 && ball2) {
|
||||||
|
outtake3();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public int greens() {
|
||||||
|
int num = 0;
|
||||||
|
|
||||||
|
if (green0){num++;}
|
||||||
|
|
||||||
|
if (green1){num++;}
|
||||||
|
|
||||||
|
|
||||||
|
if (green2){num++;}
|
||||||
|
|
||||||
|
return num;
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public int outtakePurple(int secLast, int Last) {
|
||||||
|
if (!green2 && (secLast!=3) && (Last!=3)) {
|
||||||
|
outtake3();
|
||||||
|
return 3;
|
||||||
|
} else if (!green1 && (secLast!=2) && (Last!=2)){
|
||||||
|
outtake2();
|
||||||
|
return 2;
|
||||||
|
} else if (!green0 && (secLast!=1) && (Last!=1)) {
|
||||||
|
outtake1();
|
||||||
|
return 1;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
if (secLast!=1 && Last!= 1){
|
||||||
|
outtake1();
|
||||||
|
return 1;
|
||||||
|
} else if (secLast!=2 && Last!=2){
|
||||||
|
outtake2();
|
||||||
|
return 2;
|
||||||
|
} else {
|
||||||
|
outtake3();
|
||||||
|
return 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
if (position !=0.501) {
|
||||||
|
|
||||||
|
s1.setPosition(position);
|
||||||
|
s2.setPosition(1 - position);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (telemetryOn) {
|
||||||
|
colorSensorTelemetry();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
public interface Subsystem {
|
||||||
|
|
||||||
|
public void update();
|
||||||
|
}
|
||||||
@@ -0,0 +1,58 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystems;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
public class Transfer implements Subsystem{
|
||||||
|
|
||||||
|
private final Servo servo;
|
||||||
|
|
||||||
|
private final DcMotorEx transfer;
|
||||||
|
|
||||||
|
private double motorPow = 0.0;
|
||||||
|
|
||||||
|
private double servoPos = 0.501;
|
||||||
|
|
||||||
|
public Transfer (Robot robot){
|
||||||
|
|
||||||
|
this.servo = robot.transferServo;
|
||||||
|
|
||||||
|
this.transfer = robot.transfer;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTransferPosition(double pos){
|
||||||
|
this.servoPos = pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setTransferPower (double pow){
|
||||||
|
this.motorPow = pow;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void transferOut(){
|
||||||
|
this.setTransferPosition(transferServo_out);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void transferIn(){
|
||||||
|
this.setTransferPosition(transferServo_in);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void update() {
|
||||||
|
|
||||||
|
if (servoPos!=0.501){
|
||||||
|
servo.setPosition(servoPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.setPower(motorPow);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -10,7 +10,6 @@ import com.acmerobotics.roadrunner.Pose2d;
|
|||||||
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
||||||
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
|
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
|
||||||
import com.arcrobotics.ftclib.gamepad.ToggleButtonReader;
|
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.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
@@ -25,8 +24,8 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
@Disabled
|
|
||||||
public class old extends LinearOpMode {
|
public class TeleopV1 extends LinearOpMode {
|
||||||
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
|
|
||||||
@@ -790,4 +789,3 @@ public class old extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -1,896 +0,0 @@
|
|||||||
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.setPosition(spindexPID);
|
|
||||||
robot.spin2.setPosition(-spindexPID);
|
|
||||||
} else{
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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,35 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
|
||||||
|
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.subsystems.Transfer;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
public class TransferTest extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
|
||||||
|
Transfer transfer;
|
||||||
|
|
||||||
|
public static double pos = 0.40;
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
transfer = new Transfer(robot);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()){
|
||||||
|
transfer.setTransferPosition(pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,59 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
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;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.AprilTag;
|
||||||
|
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class WebcamTest extends LinearOpMode {
|
||||||
|
|
||||||
|
AprilTag webcam;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
webcam = new AprilTag(robot, TELE);
|
||||||
|
|
||||||
|
webcam.turnTelemetryOn(true);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
while(opModeInInit()){
|
||||||
|
|
||||||
|
webcam.initTelemetry();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
if(isStopRequested()) return;
|
||||||
|
|
||||||
|
|
||||||
|
while (opModeIsActive()){
|
||||||
|
|
||||||
|
webcam.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,37 +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.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();
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,66 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.colorFilterAlpha;
|
|
||||||
|
|
||||||
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());
|
|
||||||
double color1Distance = 0;
|
|
||||||
double color2Distance = 0;
|
|
||||||
double color3Distance = 0;
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
while(opModeIsActive()){
|
|
||||||
double green1 = robot.color1.getNormalizedColors().green;
|
|
||||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
|
||||||
double red1 = robot.color1.getNormalizedColors().red;
|
|
||||||
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
|
||||||
|
|
||||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
|
||||||
TELE.addData("Color1 distance (mm)", color1Distance);
|
|
||||||
|
|
||||||
// ----- COLOR 2 -----
|
|
||||||
double green2 = robot.color2.getNormalizedColors().green;
|
|
||||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
|
||||||
double red2 = robot.color2.getNormalizedColors().red;
|
|
||||||
double dist2 = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
color2Distance = (colorFilterAlpha * dist2) + ((1-colorFilterAlpha) * color2Distance);
|
|
||||||
|
|
||||||
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
|
||||||
TELE.addData("Color2 distance (mm)", color2Distance);
|
|
||||||
|
|
||||||
// ----- COLOR 3 -----
|
|
||||||
double green3 = robot.color3.getNormalizedColors().green;
|
|
||||||
double blue3 = robot.color3.getNormalizedColors().blue;
|
|
||||||
double red3 = robot.color3.getNormalizedColors().red;
|
|
||||||
double dist3 = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
color3Distance = (colorFilterAlpha * dist3) + ((1-colorFilterAlpha) * color3Distance);
|
|
||||||
|
|
||||||
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
|
||||||
TELE.addData("Color3 distance (mm)", color3Distance);
|
|
||||||
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,222 +0,0 @@
|
|||||||
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;
|
|
||||||
|
|
||||||
|
|
||||||
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.setPosition(manualPow);
|
|
||||||
robot.spin2.setPosition(-manualPow);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(-manualPow);
|
|
||||||
robot.spin2.setPosition(manualPow);
|
|
||||||
}
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
stamp = getRuntime();
|
|
||||||
TELE.addData("Reverse?", reverse);
|
|
||||||
TELE.update();
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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.setPosition(powPID);
|
|
||||||
robot.spin2.setPosition(-powPID);
|
|
||||||
|
|
||||||
steadySpin = false;
|
|
||||||
wasMoving = true; // remember we were moving
|
|
||||||
stamp = getRuntime();
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(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;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,69 +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.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
|
||||||
//TODO: fix to get the apriltag that it is reading
|
|
||||||
public class LimelightTest extends LinearOpMode {
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
Turret turret;
|
|
||||||
Robot robot;
|
|
||||||
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 4 is for red track; DO NOT USE 3
|
|
||||||
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
|
||||||
public static boolean turretMode = false;
|
|
||||||
public static double turretPos = 0.501;
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
robot.limelight.pipelineSwitch(pipeline);
|
|
||||||
waitForStart();
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
while (opModeIsActive()){
|
|
||||||
if (mode == 0){
|
|
||||||
robot.limelight.pipelineSwitch(pipeline);
|
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (mode == 1){
|
|
||||||
int obeliskID = turret.detectObelisk();
|
|
||||||
TELE.addData("Limelight ID", obeliskID);
|
|
||||||
TELE.update();
|
|
||||||
} else if (mode == 2 || mode == 3){ // Use redAlliance variable to switch between red and blue
|
|
||||||
double tx = turret.getBearing();
|
|
||||||
double ty = turret.getTy();
|
|
||||||
double x = turret.getLimelightX();
|
|
||||||
double y = turret.getLimelightY();
|
|
||||||
TELE.addData("tx", tx);
|
|
||||||
TELE.addData("ty", ty);
|
|
||||||
TELE.addData("x", x);
|
|
||||||
TELE.addData("y", y);
|
|
||||||
TELE.update();
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (turretMode){
|
|
||||||
if (turretPos != 0.501){
|
|
||||||
turret.manualSetTurret(turretPos);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,62 +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.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;
|
|
||||||
|
|
||||||
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.setPosition(pid);
|
|
||||||
robot.spin2.setPosition(-pid);
|
|
||||||
}
|
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
|
||||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
|
||||||
telemetry.addData("target", target);
|
|
||||||
telemetry.addData("Mode", mode);
|
|
||||||
telemetry.update();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,71 +1,85 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
|
||||||
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.teleop.TeleopV3.spinSpeedIncrease;
|
|
||||||
|
|
||||||
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.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.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
@TeleOp
|
||||||
|
@Config
|
||||||
public class ShooterTest extends LinearOpMode {
|
public class ShooterTest extends LinearOpMode {
|
||||||
public static int mode = 1;
|
|
||||||
public static double parameter = 0.0;
|
|
||||||
// --- CONSTANTS YOU TUNE ---
|
|
||||||
|
|
||||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
Robot robot;
|
||||||
public static double Velocity = 0.0;
|
|
||||||
public static double P = 255.0;
|
public static double pow = 0.0;
|
||||||
public static double I = 0.0;
|
public static double vel = 0.0;
|
||||||
public static double D = 0.0;
|
public static double ecpr = 1024.0; // CPR of the encoder
|
||||||
public static double F = 7.5;
|
public static double hoodPos = 0.5;
|
||||||
public static double transferPower = 1.0;
|
public static double turretPos = 0.9;
|
||||||
public static double hoodPos = 0.501;
|
|
||||||
public static double turretPos = 0.501;
|
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 boolean shoot = false;
|
||||||
|
|
||||||
public static boolean intake = false;
|
public static int spindexPos = 1;
|
||||||
Robot robot;
|
|
||||||
Flywheel flywheel;
|
|
||||||
Servos servo;
|
|
||||||
|
|
||||||
double shootStamp = 0.0;
|
public static boolean intake = true;
|
||||||
boolean shootAll = false;
|
|
||||||
|
|
||||||
public double spinPow = 0.09;
|
public static int tolerance = 50;
|
||||||
|
|
||||||
public static boolean enableHoodAutoOpen = false;
|
double stamp = 0.0;
|
||||||
public double hoodAdjust = 0.0;
|
|
||||||
public static double hoodAdjustFactor = 1.0;
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
private int shooterTicker = 0;
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
Spindexer spindexer ;
|
public static double distance = 50;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
DcMotorEx leftShooter = robot.shooter1;
|
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
|
||||||
spindexer = new Spindexer(hardwareMap);
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
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();
|
waitForStart();
|
||||||
|
|
||||||
@@ -73,87 +87,124 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
if (mode == 0) {
|
ticker++;
|
||||||
rightShooter.setPower(parameter);
|
|
||||||
leftShooter.setPower(parameter);
|
if (AutoTrack){
|
||||||
} else if (mode == 1) {
|
hoodPos = hoodAnglePrediction(distance);
|
||||||
flywheel.setPIDF(P, I, D, F);
|
vel = velPrediction(distance);
|
||||||
flywheel.manageFlywheel((int) Velocity);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
|
||||||
if (enableHoodAutoOpen) {
|
|
||||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
shooter.setShooterMode(flyMode);
|
||||||
} else {
|
|
||||||
robot.hood.setPosition(hoodPos);
|
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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (intake) {
|
double penguin = 0;
|
||||||
robot.intake.setPower(1);
|
if (ticker % 8 ==0){
|
||||||
|
penguin = shooter.getECPRPosition();
|
||||||
} else {
|
stamp = getRuntime();
|
||||||
robot.intake.setPower(0);
|
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) {
|
if (shoot) {
|
||||||
shootStamp = getRuntime();
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
shootAll = true;
|
|
||||||
shoot = false;
|
|
||||||
robot.transfer.setPower(transferPower);
|
|
||||||
shooterTicker = 0;
|
|
||||||
}
|
|
||||||
if (shootAll) {
|
|
||||||
|
|
||||||
//intake = false;
|
|
||||||
//reject = false;
|
|
||||||
|
|
||||||
// TODO: Change starting position based on desired order to shoot green ball
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
if (getRuntime() - shootStamp < 3.5) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servo.spinEqual(spinStartPos)){
|
|
||||||
robot.spin1.setPosition(spinStartPos);
|
|
||||||
robot.spin2.setPosition(1-spinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
shootAll = false;
|
|
||||||
shooterTicker = 0;
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
spindexer.processIntake();
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
shooter.update();
|
||||||
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.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();
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,50 +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.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@Autonomous
|
|
||||||
@Config
|
|
||||||
public class TurretTest extends LinearOpMode {
|
|
||||||
public static boolean zeroTurr = false;
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
Robot robot = new Robot(hardwareMap);
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
|
||||||
);
|
|
||||||
|
|
||||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
|
||||||
|
|
||||||
while(opModeIsActive()){
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
turret.trackGoal(drive.localizer.getPose());
|
|
||||||
|
|
||||||
TELE.addData("tpos", turret.getTurrPos());
|
|
||||||
TELE.addData("Limelight tx", turret.getBearing());
|
|
||||||
TELE.addData("Limelight ty", turret.getTy());
|
|
||||||
TELE.addData("Limelight X", turret.getLimelightX());
|
|
||||||
TELE.addData("Limelight Y", turret.getLimelightY());
|
|
||||||
|
|
||||||
if(zeroTurr){
|
|
||||||
turret.zeroTurretEncoder();
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,210 +0,0 @@
|
|||||||
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;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,104 +0,0 @@
|
|||||||
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
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -5,17 +5,15 @@ import com.qualcomm.hardware.rev.RevColorSensorV3;
|
|||||||
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;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
public class ConfigureColorRangefinder extends LinearOpMode {
|
public class ConfigureColorRangefinder extends LinearOpMode {
|
||||||
|
|
||||||
|
public static int LED_Brightness = 50;
|
||||||
|
|
||||||
|
public static int lowerGreen = 110;
|
||||||
|
|
||||||
public static double lowerBound = 80;
|
public static int higherGreen = 150;
|
||||||
public static double higherBound = 120;
|
|
||||||
|
|
||||||
public static int led = 0;
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -24,11 +22,12 @@ public class ConfigureColorRangefinder extends LinearOpMode {
|
|||||||
/* 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.DISTANCE, 3, 20);
|
crf.setPin1Digital(ColorRangefinder.DigitalMode.DISTANCE, 0, 40); // green
|
||||||
crf.setPin1Digital(ColorRangefinder.DigitalMode.HSV, lowerBound, higherBound); // green
|
crf.setPin0Digital(ColorRangefinder.DigitalMode.HSV, higherGreen / 360.0 * 255, 360 / 360.0 * 255); // purple
|
||||||
crf.setPin1DigitalMaxDistance(ColorRangefinder.DigitalMode.HSV, 25); //25 mm or closer
|
crf.setPin0Digital(ColorRangefinder.DigitalMode.HSV, 0, lowerGreen/360.0 * 255);
|
||||||
crf.setLedBrightness(led);
|
crf.setPin0DigitalMaxDistance(ColorRangefinder.DigitalMode.HSV, 40); // 10mm or closer requirement
|
||||||
|
|
||||||
|
crf.setLedBrightness(LED_Brightness);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -143,6 +142,7 @@ class ColorRangefinder {
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* Read distance via I2C
|
* Read distance via I2C
|
||||||
|
*
|
||||||
* @return distance in millimeters
|
* @return distance in millimeters
|
||||||
*/
|
*/
|
||||||
public double readDistance() {
|
public double readDistance() {
|
||||||
|
|||||||
@@ -1,81 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
|
||||||
|
|
||||||
public class Flywheel {
|
|
||||||
Robot robot;
|
|
||||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
|
||||||
double velo = 0.0;
|
|
||||||
public double velo1 = 0.0;
|
|
||||||
public double velo2 = 0.0;
|
|
||||||
double targetVelocity = 0.0;
|
|
||||||
double powPID = 0.0;
|
|
||||||
boolean steady = false;
|
|
||||||
public Flywheel (HardwareMap hardwareMap) {
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
shooterPIDF1 = new PIDFCoefficients
|
|
||||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
|
||||||
shooterPIDF2 = new PIDFCoefficients
|
|
||||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
|
||||||
}
|
|
||||||
|
|
||||||
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) {
|
|
||||||
shooterPIDF1.p = p;
|
|
||||||
shooterPIDF1.i = i;
|
|
||||||
shooterPIDF1.d = d;
|
|
||||||
shooterPIDF1.f = f;
|
|
||||||
shooterPIDF2.p = p;
|
|
||||||
shooterPIDF2.i = i;
|
|
||||||
shooterPIDF2.d = d;
|
|
||||||
shooterPIDF2.f = f;
|
|
||||||
}
|
|
||||||
|
|
||||||
// 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;
|
|
||||||
|
|
||||||
// Add code here to set PIDF based on desired RPM
|
|
||||||
|
|
||||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
|
||||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
|
||||||
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.shooter2.getVelocity());
|
|
||||||
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()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,110 +0,0 @@
|
|||||||
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() {
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,41 +1,31 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
|
||||||
|
|
||||||
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.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
|
||||||
|
|
||||||
@TeleOp
|
@TeleOp
|
||||||
@Config
|
@Config
|
||||||
public class PositionalServoProgrammer extends LinearOpMode {
|
public class PositionalServoProgrammer extends LinearOpMode {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Servos servo;
|
|
||||||
|
|
||||||
public static double spindexPos = 0.501;
|
public static double spindexPos = 0.501;
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
public static double transferPos = 0.501;
|
public static double transferPos = 0.501;
|
||||||
public static double hoodPos = 0.501;
|
public static double hoodPos = 0.501;
|
||||||
public static double light = 0.501;
|
|
||||||
|
|
||||||
Turret turret;
|
|
||||||
|
|
||||||
|
public static double scalar = 1.112;
|
||||||
|
public static double restPos = 0.158;
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight );
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
while (opModeIsActive()){
|
while (opModeIsActive()){
|
||||||
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos)){
|
if (spindexPos != 0.501){
|
||||||
robot.spin1.setPosition(spindexPos);
|
robot.spin1.setPosition(spindexPos);
|
||||||
robot.spin2.setPosition(1-spindexPos);
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
}
|
}
|
||||||
@@ -49,27 +39,14 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
if (hoodPos != 0.501){
|
if (hoodPos != 0.501){
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos);
|
||||||
}
|
}
|
||||||
if (light !=0.501){
|
TELE.addData("spindexer", scalar*((robot.spin1Pos.getVoltage() - restPos) / 3.3));
|
||||||
robot.light.setPosition(light);
|
TELE.addData("hood", 1-scalar*((robot.hoodPos.getVoltage() - restPos) / 3.3));
|
||||||
}
|
TELE.addData("transferServo", scalar*((robot.transferServoPos.getVoltage() - restPos) / 3.3));
|
||||||
// To check configuration of spindexer:
|
TELE.addData("turret", scalar*((robot.turr1Pos.getVoltage() - restPos) / 3.3));
|
||||||
// Set "mode" to 1 and spindexPow to 0.1
|
TELE.addData("spindexerA", robot.spin1Pos.getVoltage());
|
||||||
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
TELE.addData("hoodA", robot.hoodPos.getVoltage());
|
||||||
// Do the previous test again to confirm
|
TELE.addData("transferServoA", robot.transferServoPos.getVoltage());
|
||||||
// Set "mode" to 0 but keep spindexPos at 0.501
|
TELE.addData("turretA", robot.turr1Pos.getVoltage());
|
||||||
// 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", robot.turr1.getPosition());
|
|
||||||
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("tpos ", turret.getTurrPos() );
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,66 +1,94 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.arcrobotics.ftclib.hardware.ServoEx;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||||
import com.qualcomm.robotcore.hardware.CRServo;
|
|
||||||
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.DcMotorImplEx;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
import com.qualcomm.robotcore.hardware.I2cDevice;
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.vision.VisionPortal;
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||||
|
import org.openftc.easyopencv.OpenCvWebcam;
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Robot {
|
public class Robot {
|
||||||
|
|
||||||
//Initialize Public Components
|
//Initialize Public Components
|
||||||
|
|
||||||
public static boolean usingLimelight = true;
|
|
||||||
public static boolean usingCamera = false;
|
|
||||||
public DcMotorEx frontLeft;
|
public DcMotorEx frontLeft;
|
||||||
public DcMotorEx frontRight;
|
public DcMotorEx frontRight;
|
||||||
|
|
||||||
public DcMotorEx backLeft;
|
public DcMotorEx backLeft;
|
||||||
|
|
||||||
public DcMotorEx backRight;
|
public DcMotorEx backRight;
|
||||||
|
|
||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
|
|
||||||
public DcMotorEx transfer;
|
public DcMotorEx transfer;
|
||||||
public PIDFCoefficients shooterPIDF;
|
|
||||||
public double shooterPIDF_P = 255.0;
|
|
||||||
public double shooterPIDF_I = 0.0;
|
|
||||||
public double shooterPIDF_D = 0.0;
|
|
||||||
public double shooterPIDF_F = 7.5;
|
|
||||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
|
||||||
public DcMotorEx shooter1;
|
public DcMotorEx shooter1;
|
||||||
public DcMotorEx shooter2;
|
public DcMotorEx shooter2;
|
||||||
public Servo hood;
|
public Servo hood;
|
||||||
|
|
||||||
public Servo transferServo;
|
public Servo transferServo;
|
||||||
|
|
||||||
|
public Servo rejecter;
|
||||||
|
|
||||||
public Servo turr1;
|
public Servo turr1;
|
||||||
|
|
||||||
public Servo turr2;
|
public Servo turr2;
|
||||||
|
|
||||||
public Servo spin1;
|
public Servo spin1;
|
||||||
|
|
||||||
public Servo spin2;
|
public Servo spin2;
|
||||||
|
|
||||||
|
public DigitalChannel pin0;
|
||||||
|
|
||||||
|
public DigitalChannel pin1;
|
||||||
|
public DigitalChannel pin2;
|
||||||
|
public DigitalChannel pin3;
|
||||||
|
public DigitalChannel pin4;
|
||||||
|
|
||||||
|
public DigitalChannel pin5;
|
||||||
|
|
||||||
|
public AnalogInput analogInput;
|
||||||
|
|
||||||
|
public AnalogInput analogInput2;
|
||||||
|
|
||||||
public AnalogInput spin1Pos;
|
public AnalogInput spin1Pos;
|
||||||
|
|
||||||
public AnalogInput spin2Pos;
|
public AnalogInput spin2Pos;
|
||||||
|
|
||||||
|
public AnalogInput hoodPos;
|
||||||
|
|
||||||
public AnalogInput turr1Pos;
|
public AnalogInput turr1Pos;
|
||||||
|
|
||||||
|
public AnalogInput turr2Pos;
|
||||||
|
|
||||||
public AnalogInput transferServoPos;
|
public AnalogInput transferServoPos;
|
||||||
|
|
||||||
public AprilTagProcessor aprilTagProcessor;
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
|
|
||||||
public WebcamName webcam;
|
public WebcamName webcam;
|
||||||
|
|
||||||
|
public DcMotorEx shooterEncoder;
|
||||||
|
|
||||||
public RevColorSensorV3 color1;
|
public RevColorSensorV3 color1;
|
||||||
|
|
||||||
public RevColorSensorV3 color2;
|
public RevColorSensorV3 color2;
|
||||||
|
|
||||||
public RevColorSensorV3 color3;
|
public RevColorSensorV3 color3;
|
||||||
public Limelight3A limelight;
|
|
||||||
public Servo light;
|
|
||||||
|
|
||||||
public Robot(HardwareMap hardwareMap) {
|
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");
|
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
|
||||||
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
||||||
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
||||||
@@ -74,37 +102,50 @@ public class Robot {
|
|||||||
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
|
||||||
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
||||||
|
rejecter = hardwareMap.get(Servo.class, "rejecter");
|
||||||
|
|
||||||
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
||||||
|
|
||||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
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);
|
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);
|
|
||||||
shooter1.setVelocity(0);
|
|
||||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
|
||||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
|
||||||
shooter2.setVelocity(0);
|
|
||||||
|
|
||||||
hood = hardwareMap.get(Servo.class, "hood");
|
hood = hardwareMap.get(Servo.class, "hood");
|
||||||
|
|
||||||
|
hoodPos = hardwareMap.get(AnalogInput.class, "hoodPos");
|
||||||
|
|
||||||
turr1 = hardwareMap.get(Servo.class, "t1");
|
turr1 = hardwareMap.get(Servo.class, "t1");
|
||||||
|
|
||||||
|
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos");
|
||||||
|
|
||||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||||
|
|
||||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
turr2Pos = hardwareMap.get(AnalogInput.class, "t2Pos");
|
||||||
|
|
||||||
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
spin1 = hardwareMap.get(Servo.class, "spin1");
|
||||||
spin1 = hardwareMap.get(Servo.class, "spin2");
|
|
||||||
|
|
||||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
spin2 = hardwareMap.get(Servo.class, "spin1");
|
spin2 = hardwareMap.get(Servo.class, "spin2");
|
||||||
|
|
||||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||||
|
|
||||||
|
pin0 = hardwareMap.get(DigitalChannel.class, "pin0");
|
||||||
|
|
||||||
|
pin1 = hardwareMap.get(DigitalChannel.class, "pin1");
|
||||||
|
|
||||||
|
pin2 = hardwareMap.get(DigitalChannel.class, "pin2");
|
||||||
|
|
||||||
|
pin3 = hardwareMap.get(DigitalChannel.class, "pin3");
|
||||||
|
|
||||||
|
pin4 = hardwareMap.get(DigitalChannel.class, "pin4");
|
||||||
|
|
||||||
|
pin5 = hardwareMap.get(DigitalChannel.class, "pin5");
|
||||||
|
|
||||||
|
analogInput = hardwareMap.get(AnalogInput.class, "analog");
|
||||||
|
|
||||||
|
analogInput2 = hardwareMap.get(AnalogInput.class, "analog2");
|
||||||
|
|
||||||
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||||
|
|
||||||
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
||||||
@@ -112,21 +153,15 @@ public class Robot {
|
|||||||
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
||||||
|
|
||||||
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
|
||||||
|
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||||
|
|
||||||
|
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||||
|
|
||||||
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
||||||
|
|
||||||
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
|
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
|
||||||
|
|
||||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
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();
|
|
||||||
}
|
|
||||||
|
|
||||||
light = hardwareMap.get(Servo.class, "light");
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,55 +0,0 @@
|
|||||||
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 = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
|
||||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
|
||||||
public static double spin_scalar = 1.112;
|
|
||||||
public static double spin_restPos = 0.155;
|
|
||||||
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()
|
|
||||||
// TODO: set the restPos and scalar
|
|
||||||
public double getSpinPos() {
|
|
||||||
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setSpinPos(double pos) {
|
|
||||||
|
|
||||||
return pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
|
||||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getTurrPos() {
|
|
||||||
return 1.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
|
||||||
return 1.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,577 +0,0 @@
|
|||||||
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.Color.*;
|
|
||||||
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.constants.Types;
|
|
||||||
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;
|
|
||||||
|
|
||||||
public double spindexerWiggle = 0.01;
|
|
||||||
|
|
||||||
public double spindexerOuttakeWiggle = 0.01;
|
|
||||||
private double prevPos = 0.0;
|
|
||||||
public double spindexerPosOffset = 0.00;
|
|
||||||
public Types.Motif desiredMotif = Types.Motif.NONE;
|
|
||||||
// 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_START,
|
|
||||||
UNKNOWN_MOVE,
|
|
||||||
UNKNOWN_DETECT,
|
|
||||||
INTAKE,
|
|
||||||
FINDNEXT,
|
|
||||||
MOVING,
|
|
||||||
FULL,
|
|
||||||
SHOOTNEXT,
|
|
||||||
SHOOTMOVING,
|
|
||||||
SHOOTWAIT,
|
|
||||||
SHOOT_ALL_PREP,
|
|
||||||
SHOOT_ALL_READY
|
|
||||||
}
|
|
||||||
|
|
||||||
int shootWaitCount = 0;
|
|
||||||
|
|
||||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
|
||||||
public IntakeState prevIntakeState = IntakeState.UNKNOWN_START;
|
|
||||||
public int unknownColorDetect = 0;
|
|
||||||
public 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+spindexerPosOffset,
|
|
||||||
spindexer_outtakeBall2+spindexerPosOffset,
|
|
||||||
spindexer_outtakeBall3+spindexerPosOffset};
|
|
||||||
|
|
||||||
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_START;
|
|
||||||
}
|
|
||||||
|
|
||||||
// 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 detectRearColor, boolean detectFrontColor) {
|
|
||||||
|
|
||||||
boolean newPos1Detection = false;
|
|
||||||
int spindexerBallPos = 0;
|
|
||||||
|
|
||||||
// Read Distances
|
|
||||||
double dRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
distanceRearCenter = (colorFilterAlpha * dRearCenter) + ((1-colorFilterAlpha) * distanceRearCenter);
|
|
||||||
double dFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
distanceFrontDriver = (colorFilterAlpha * dFrontDriver) + ((1-colorFilterAlpha) * distanceFrontDriver);
|
|
||||||
double dFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
|
||||||
|
|
||||||
// Position 1
|
|
||||||
if (distanceRearCenter < 60) {
|
|
||||||
|
|
||||||
// Mark Ball Found
|
|
||||||
newPos1Detection = true;
|
|
||||||
|
|
||||||
if (detectRearColor) {
|
|
||||||
// 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.38) {
|
|
||||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// Position 2
|
|
||||||
// Find which ball position this is in the spindexer
|
|
||||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
|
||||||
if (distanceFrontDriver < 50) {
|
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
|
||||||
if (detectFrontColor) {
|
|
||||||
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) {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} 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 < 29) {
|
|
||||||
|
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
|
||||||
if (detectFrontColor) {
|
|
||||||
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.42) {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} 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;
|
|
||||||
}
|
|
||||||
// Has code to unjam spindexer
|
|
||||||
private void moveSpindexerToPos(double pos) {
|
|
||||||
robot.spin1.setPosition(pos);
|
|
||||||
robot.spin2.setPosition(1-pos);
|
|
||||||
double currentPos = servos.getSpinPos();
|
|
||||||
if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){
|
|
||||||
// if (currentPos > pos){
|
|
||||||
// robot.spin1.setPosition(servos.getSpinPos() + 0.05);
|
|
||||||
// robot.spin2.setPosition(1 - servos.getSpinPos() - 0.05);
|
|
||||||
// } else {
|
|
||||||
// robot.spin1.setPosition(servos.getSpinPos() - 0.05);
|
|
||||||
// robot.spin2.setPosition(1 - servos.getSpinPos() + 0.05);
|
|
||||||
// }
|
|
||||||
}
|
|
||||||
prevPos = currentPos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void stopSpindexer() {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public void ballCounterLight(){
|
|
||||||
int counter = 0;
|
|
||||||
if (!ballPositions[0].isEmpty){
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
if (!ballPositions[1].isEmpty){
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
if (!ballPositions[2].isEmpty){
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
if (counter == 3){
|
|
||||||
robot.light.setPosition(Light3);
|
|
||||||
} else if (counter == 2){
|
|
||||||
robot.light.setPosition(Light2);
|
|
||||||
} else if (counter == 1){
|
|
||||||
robot.light.setPosition(Light1);
|
|
||||||
} else {
|
|
||||||
robot.light.setPosition(Light0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean slotIsEmpty(int slot){
|
|
||||||
return !ballPositions[slot].isEmpty;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean isFull () {
|
|
||||||
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
|
||||||
}
|
|
||||||
public boolean processIntake() {
|
|
||||||
|
|
||||||
switch (currentIntakeState) {
|
|
||||||
case UNKNOWN_START:
|
|
||||||
// For now just set position ONE if UNKNOWN
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
moveSpindexerToPos(intakePositions[0]);
|
|
||||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
|
|
||||||
break;
|
|
||||||
case UNKNOWN_MOVE:
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
|
||||||
stopSpindexer();
|
|
||||||
unknownColorDetect = 0;
|
|
||||||
} else {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case UNKNOWN_DETECT:
|
|
||||||
if (unknownColorDetect >5) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
} else {
|
|
||||||
//detectBalls(true, true);
|
|
||||||
unknownColorDetect++;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case INTAKE:
|
|
||||||
// Ready for intake and Detecting a New Ball
|
|
||||||
if (detectBalls(true, false)) {
|
|
||||||
ballPositions[commandedIntakePosition].isEmpty = false;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
} else {
|
|
||||||
// Maintain Position
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
|
|
||||||
}
|
|
||||||
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)) {
|
|
||||||
if (ballPositions[0].isEmpty) {
|
|
||||||
// Position 1
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
|
||||||
//if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
|
||||||
if (ballPositions[1].isEmpty) {
|
|
||||||
// Position 2
|
|
||||||
commandedIntakePosition = 1;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
|
||||||
if (ballPositions[2].isEmpty) {
|
|
||||||
// Position 3
|
|
||||||
commandedIntakePosition = 2;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
|
||||||
// Full
|
|
||||||
//commandedIntakePosition = bestFitMotif();
|
|
||||||
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(false, false);
|
|
||||||
} else {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case FULL:
|
|
||||||
// Double Check Colors
|
|
||||||
detectBalls(false, false); // Minimize hardware calls
|
|
||||||
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
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOT_ALL_PREP:
|
|
||||||
// We get here with function call to prepareToShootMotif
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
if (!servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
moveSpindexerToPos(outakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOT_ALL_READY: // Not used
|
|
||||||
// Double Check Colors
|
|
||||||
//detectBalls(false, false); // Minimize hardware calls
|
|
||||||
if (ballPositions[0].isEmpty && ballPositions[1].isEmpty && ballPositions[2].isEmpty) {
|
|
||||||
// All ball shot move to intake state
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
|
||||||
}
|
|
||||||
// Maintain Position
|
|
||||||
moveSpindexerToPos(outakePositions[commandedIntakePosition]);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTNEXT:
|
|
||||||
// Find Next Open Position and start movement
|
|
||||||
if (!ballPositions[0].isEmpty) {
|
|
||||||
// Position 1
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else if (!ballPositions[1].isEmpty) {
|
|
||||||
// Position 2
|
|
||||||
commandedIntakePosition = 1;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else if (!ballPositions[2].isEmpty) {
|
|
||||||
// Position 3
|
|
||||||
commandedIntakePosition = 2;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else {
|
|
||||||
// Empty return to intake state
|
|
||||||
currentIntakeState = IntakeState.FINDNEXT;
|
|
||||||
}
|
|
||||||
moveSpindexerToPos(outakePositions[commandedIntakePosition]);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTMOVING:
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
|
||||||
} else {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
moveSpindexerToPos(outakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTWAIT:
|
|
||||||
double shootWaitMax = 4;
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (prevIntakeState != currentIntakeState) {
|
|
||||||
if (commandedIntakePosition==2) {
|
|
||||||
shootWaitMax = 5;
|
|
||||||
}
|
|
||||||
shootWaitCount = 0;
|
|
||||||
} else {
|
|
||||||
shootWaitCount++;
|
|
||||||
}
|
|
||||||
// wait 10 cycles
|
|
||||||
if (shootWaitCount > shootWaitMax) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
|
||||||
ballPositions[commandedIntakePosition].isEmpty = true;
|
|
||||||
shootWaitCount = 0;
|
|
||||||
//stopSpindexer();
|
|
||||||
//detectBalls(true, false);
|
|
||||||
}
|
|
||||||
// Keep moving the spindexer
|
|
||||||
spindexerOuttakeWiggle *= -1.01;
|
|
||||||
moveSpindexerToPos(outakePositions[commandedIntakePosition]+spindexerOuttakeWiggle);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
// Statements to execute if no case matches
|
|
||||||
}
|
|
||||||
|
|
||||||
prevIntakeState = currentIntakeState;
|
|
||||||
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
|
||||||
//TELE.update();
|
|
||||||
// Signal a successful intake
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setDesiredMotif (Types.Motif newMotif) {
|
|
||||||
desiredMotif = newMotif;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns the best fit for the motiff
|
|
||||||
public int bestFitMotif () {
|
|
||||||
switch (desiredMotif) {
|
|
||||||
case GPP:
|
|
||||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
|
||||||
return 2;
|
|
||||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
|
||||||
return 0;
|
|
||||||
} else {
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
//break;
|
|
||||||
case PGP:
|
|
||||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
|
||||||
return 0;
|
|
||||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
|
||||||
return 1;
|
|
||||||
} else {
|
|
||||||
return 2;
|
|
||||||
}
|
|
||||||
//break;
|
|
||||||
case PPG:
|
|
||||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
|
||||||
return 1;
|
|
||||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
|
||||||
return 0;
|
|
||||||
} else {
|
|
||||||
return 2;
|
|
||||||
}
|
|
||||||
//break;
|
|
||||||
case NONE:
|
|
||||||
return 0;
|
|
||||||
//break;
|
|
||||||
}
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void prepareToShootMotif () {
|
|
||||||
commandedIntakePosition = bestFitMotif();
|
|
||||||
}
|
|
||||||
|
|
||||||
public void prepareShootAll(){
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_PREP;
|
|
||||||
}
|
|
||||||
public void shootAll () {
|
|
||||||
ballPositions[0].isEmpty = false;
|
|
||||||
ballPositions[1].isEmpty = false;
|
|
||||||
ballPositions[2].isEmpty = false;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean shootAllComplete ()
|
|
||||||
{
|
|
||||||
return ((currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_PREP) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_READY) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOTMOVING) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOTNEXT) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOTWAIT));
|
|
||||||
}
|
|
||||||
|
|
||||||
void shootAllToIntake () {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void update()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
public BallColor GetFrontDriverColor () {
|
|
||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()]].ballColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
public BallColor GetFrontPassengerColor () {
|
|
||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()]].ballColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
public BallColor GetRearCenterColor () {
|
|
||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,219 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import android.provider.Settings;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
|
|
||||||
public class Targeting {
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
|
|
||||||
double cancelOffsetX = 0.0; // was -40.0
|
|
||||||
double cancelOffsetY = 0.0; // was 7.0
|
|
||||||
double unitConversionFactor = 0.95;
|
|
||||||
|
|
||||||
int tileSize = 24; //inches
|
|
||||||
public final int TILE_UPPER_QUARTILE = 18;
|
|
||||||
public final int TILE_LOWER_QUARTILE = 6;
|
|
||||||
|
|
||||||
public double robotInchesX, robotInchesY = 0.0;
|
|
||||||
|
|
||||||
public int robotGridX, robotGridY = 0;
|
|
||||||
|
|
||||||
|
|
||||||
public static class Settings {
|
|
||||||
public double flywheelRPM = 0.0;
|
|
||||||
public double hoodAngle = 0.0;
|
|
||||||
|
|
||||||
public Settings (double flywheelRPM, double hoodAngle) {
|
|
||||||
this.flywheelRPM = flywheelRPM;
|
|
||||||
this.hoodAngle = hoodAngle;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Known settings discovered using shooter test.
|
|
||||||
// Keep the fidelity at 1 floor tile for now but we could also half it if more
|
|
||||||
// accuracy is needed.
|
|
||||||
public static final Settings[][] KNOWNTARGETING;
|
|
||||||
static {
|
|
||||||
KNOWNTARGETING = new Settings[6][6];
|
|
||||||
// ROW 0 - Closet to the goals
|
|
||||||
KNOWNTARGETING[0][0] = new Settings (2300.0, 0.93);
|
|
||||||
KNOWNTARGETING[0][1] = new Settings (2300.0, 0.93);
|
|
||||||
KNOWNTARGETING[0][2] = new Settings (2500.0, 0.78);
|
|
||||||
KNOWNTARGETING[0][3] = new Settings (2800.0, 0.68);
|
|
||||||
KNOWNTARGETING[0][4] = new Settings (3000.0, 0.58);
|
|
||||||
KNOWNTARGETING[0][5] = new Settings (3000.0, 0.58);
|
|
||||||
// ROW 1
|
|
||||||
KNOWNTARGETING[1][0] = new Settings (2300.0, 0.93);
|
|
||||||
KNOWNTARGETING[1][1] = new Settings (2300.0, 0.93);
|
|
||||||
KNOWNTARGETING[1][2] = new Settings (2600.0, 0.78);
|
|
||||||
KNOWNTARGETING[1][3] = new Settings (2800.0, 0.62);
|
|
||||||
KNOWNTARGETING[1][4] = new Settings (3000.0, 0.55);
|
|
||||||
KNOWNTARGETING[1][5] = new Settings (3200.0, 0.50);
|
|
||||||
// ROW 2
|
|
||||||
KNOWNTARGETING[2][0] = new Settings (2500.0, 0.78);
|
|
||||||
KNOWNTARGETING[2][1] = new Settings (2500.0, 0.78);
|
|
||||||
KNOWNTARGETING[2][2] = new Settings (2700.0, 0.60);
|
|
||||||
KNOWNTARGETING[2][3] = new Settings (2900.0, 0.53);
|
|
||||||
KNOWNTARGETING[2][4] = new Settings (3100.0, 0.50);
|
|
||||||
KNOWNTARGETING[2][5] = new Settings (3100.0, 0.50);
|
|
||||||
// ROW 3
|
|
||||||
KNOWNTARGETING[3][0] = new Settings (2900.0, 0.50);
|
|
||||||
KNOWNTARGETING[3][1] = new Settings (2900.0, 0.50);
|
|
||||||
KNOWNTARGETING[3][2] = new Settings (2900.0, 0.50);
|
|
||||||
KNOWNTARGETING[3][3] = new Settings (3100.0, 0.47);
|
|
||||||
KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47);
|
|
||||||
KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47);
|
|
||||||
// ROW 4
|
|
||||||
KNOWNTARGETING[4][0] = new Settings (3100, 0.49);
|
|
||||||
KNOWNTARGETING[4][1] = new Settings (3100, 0.49);
|
|
||||||
KNOWNTARGETING[4][2] = new Settings (3100, 0.5);
|
|
||||||
KNOWNTARGETING[4][3] = new Settings (3200, 0.5);
|
|
||||||
KNOWNTARGETING[4][4] = new Settings (3250, 0.49);
|
|
||||||
KNOWNTARGETING[4][5] = new Settings (3300, 0.49);
|
|
||||||
// ROW 5
|
|
||||||
KNOWNTARGETING[5][0] = new Settings (3200, 0.48);
|
|
||||||
KNOWNTARGETING[5][1] = new Settings (3200, 0.48);
|
|
||||||
KNOWNTARGETING[5][2] = new Settings (3300, 0.48);
|
|
||||||
KNOWNTARGETING[5][3] = new Settings (3350, 0.48);
|
|
||||||
KNOWNTARGETING[5][4] = new Settings (3350, 0.48);
|
|
||||||
KNOWNTARGETING[5][5] = new Settings (3350, 0.48);
|
|
||||||
}
|
|
||||||
|
|
||||||
public Targeting()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
|
||||||
Settings recommendedSettings = new Settings(0.0, 0.0);
|
|
||||||
|
|
||||||
double cos45 = Math.cos(Math.toRadians(-45));
|
|
||||||
double sin45 = Math.sin(Math.toRadians(-45));
|
|
||||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
|
||||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
|
||||||
|
|
||||||
// Convert robot coordinates to inches
|
|
||||||
robotInchesX = rotatedX * unitConversionFactor;
|
|
||||||
robotInchesY = rotatedY * unitConversionFactor;
|
|
||||||
|
|
||||||
// Find approximate location in the grid
|
|
||||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
|
||||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
|
||||||
|
|
||||||
int remX = Math.floorMod((int)robotInchesX, tileSize);
|
|
||||||
int remY = Math.floorMod((int)robotInchesX, tileSize);
|
|
||||||
|
|
||||||
// Determine if we need to interpolate based on tile position.
|
|
||||||
// if near upper or lower quarter or tile interpolate with next tile.
|
|
||||||
int x0 = 0;
|
|
||||||
int y0 = 0;
|
|
||||||
int x1 = 0;
|
|
||||||
int y1 = 0;
|
|
||||||
interpolate = false;
|
|
||||||
if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
|
||||||
(robotGridX < 5) && (robotGridY <5)) {
|
|
||||||
// +X, +Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX;
|
|
||||||
x1 = robotGridX + 1;
|
|
||||||
y0 = robotGridY;
|
|
||||||
y1 = robotGridY + 1;
|
|
||||||
} else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
|
||||||
(robotGridX > 0) && (robotGridY > 0)) {
|
|
||||||
// -X, -Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX - 1;
|
|
||||||
x1 = robotGridX;
|
|
||||||
y0 = robotGridY - 1;
|
|
||||||
y1 = robotGridY;
|
|
||||||
} else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
|
||||||
(robotGridX < 5) && (robotGridY > 0)) {
|
|
||||||
// +X, -Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX;
|
|
||||||
x1 = robotGridX + 1;
|
|
||||||
y0 = robotGridY - 1;
|
|
||||||
y1 = robotGridY;
|
|
||||||
} else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
|
||||||
(robotGridX > 0) && (robotGridY < 5)) {
|
|
||||||
// -X, +Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX - 1;
|
|
||||||
x1 = robotGridX;
|
|
||||||
y0 = robotGridY;
|
|
||||||
y1 = robotGridY + 1;
|
|
||||||
} else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) {
|
|
||||||
// -X, Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX - 1;
|
|
||||||
x1 = robotGridX;
|
|
||||||
y0 = robotGridY;
|
|
||||||
y1 = robotGridY;
|
|
||||||
} else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) {
|
|
||||||
// X, -Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX;
|
|
||||||
x1 = robotGridX;
|
|
||||||
y0 = robotGridY - 1;
|
|
||||||
y1 = robotGridY;
|
|
||||||
} else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) {
|
|
||||||
// +X, Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX;
|
|
||||||
x1 = robotGridX + 1;
|
|
||||||
y0 = robotGridY;
|
|
||||||
y1 = robotGridY;
|
|
||||||
} else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) {
|
|
||||||
// X, +Y
|
|
||||||
interpolate = true;
|
|
||||||
x0 = robotGridX;
|
|
||||||
x1 = robotGridX;
|
|
||||||
y0 = robotGridY;
|
|
||||||
y1 = robotGridY + 1;
|
|
||||||
} else {
|
|
||||||
interpolate = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
//clamp
|
|
||||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
|
||||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
|
||||||
|
|
||||||
// basic search
|
|
||||||
if(true) { //!interpolate) {
|
|
||||||
if ((robotGridY < 6) && (robotGridX <6)) {
|
|
||||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
|
||||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
|
|
||||||
}
|
|
||||||
return recommendedSettings;
|
|
||||||
} else {
|
|
||||||
|
|
||||||
// bilinear interpolation
|
|
||||||
//int x0 = robotGridX;
|
|
||||||
//int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
|
||||||
//int y0 = robotGridY;
|
|
||||||
//int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
|
||||||
|
|
||||||
// double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
|
||||||
// double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
|
||||||
|
|
||||||
// double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM;
|
|
||||||
// double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM;
|
|
||||||
// double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM;
|
|
||||||
// double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM;
|
|
||||||
//
|
|
||||||
// double angle00 = KNOWNTARGETING[y0][x0].hoodAngle;
|
|
||||||
// double angle10 = KNOWNTARGETING[y0][x1].hoodAngle;
|
|
||||||
// double angle01 = KNOWNTARGETING[y1][x0].hoodAngle;
|
|
||||||
// double angle11 = KNOWNTARGETING[y1][x1].hoodAngle;
|
|
||||||
|
|
||||||
// recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11;
|
|
||||||
// recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11;
|
|
||||||
// Average target tiles
|
|
||||||
recommendedSettings.flywheelRPM = (KNOWNTARGETING[x0][y0].flywheelRPM + KNOWNTARGETING[x1][y1].flywheelRPM)/2.0;
|
|
||||||
recommendedSettings.hoodAngle = (KNOWNTARGETING[x0][y0].hoodAngle + KNOWNTARGETING[x1][y1].hoodAngle)/2.0;
|
|
||||||
return recommendedSettings;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,302 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
|
|
||||||
import static java.lang.Math.abs;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.arcrobotics.ftclib.controller.PIDController;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
|
||||||
|
|
||||||
import java.util.List;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Turret {
|
|
||||||
|
|
||||||
public static double turretTolerance = 0.02;
|
|
||||||
public static double turrPosScalar = 0.00011264432;
|
|
||||||
public static double turret180Range = 0.4;
|
|
||||||
public static double turrDefault = 0.4;
|
|
||||||
public static double turrMin = 0.15;
|
|
||||||
public static double turrMax = 0.85;
|
|
||||||
|
|
||||||
public static double visionCorrectionGain = 0.08; // Single tunable gain
|
|
||||||
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
|
||||||
public static double cameraBearingEqual = 0.5; // Deadband
|
|
||||||
|
|
||||||
// TODO: tune these values for limelight
|
|
||||||
|
|
||||||
public static double clampTolerance = 0.03;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
Limelight3A webcam;
|
|
||||||
|
|
||||||
double tx = 0.0;
|
|
||||||
double ty = 0.0;
|
|
||||||
double limelightPosX = 0.0;
|
|
||||||
double limelightPosY = 0.0;
|
|
||||||
private boolean lockOffset = false;
|
|
||||||
private int obeliskID = 0;
|
|
||||||
|
|
||||||
private double offset = 0.0;
|
|
||||||
private double currentTrackOffset = 0.0;
|
|
||||||
private int currentTrackCount = 0;
|
|
||||||
|
|
||||||
private double permanentOffset = 0.0;
|
|
||||||
|
|
||||||
LLResult result;
|
|
||||||
|
|
||||||
private PIDController bearingPID;
|
|
||||||
public static double B_PID_P = 0.3, B_PID_I = 0.0, B_PID_D = 0.05;
|
|
||||||
boolean bearingAligned = false;
|
|
||||||
|
|
||||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
|
||||||
this.TELE = tele;
|
|
||||||
this.robot = rob;
|
|
||||||
this.webcam = cam;
|
|
||||||
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void zeroTurretEncoder() {
|
|
||||||
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
|
||||||
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getTurrPos() {
|
|
||||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public void manualSetTurret(double pos) {
|
|
||||||
robot.turr1.setPosition(pos);
|
|
||||||
robot.turr2.setPosition(1 - pos);
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
|
||||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
|
||||||
if (redAlliance) {
|
|
||||||
webcam.pipelineSwitch(4);
|
|
||||||
} else {
|
|
||||||
webcam.pipelineSwitch(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
result = webcam.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
tx = result.getTx();
|
|
||||||
ty = result.getTy();
|
|
||||||
// MegaTag1 code for receiving position
|
|
||||||
Pose3D botpose = result.getBotpose();
|
|
||||||
if (botpose != null) {
|
|
||||||
limelightPosX = botpose.getPosition().x;
|
|
||||||
limelightPosY = botpose.getPosition().y;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getBearing() {
|
|
||||||
tx = 1000;
|
|
||||||
limelightRead();
|
|
||||||
return tx;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getTy() {
|
|
||||||
return ty;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getLimelightX() {
|
|
||||||
return limelightPosX;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getLimelightY() {
|
|
||||||
return limelightPosY;
|
|
||||||
}
|
|
||||||
|
|
||||||
public int detectObelisk() {
|
|
||||||
webcam.pipelineSwitch(1);
|
|
||||||
LLResult result = webcam.getLatestResult();
|
|
||||||
if (result != null && result.isValid()) {
|
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
|
||||||
obeliskID = fiducial.getFiducialId();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return obeliskID;
|
|
||||||
}
|
|
||||||
|
|
||||||
public int getObeliskID() {
|
|
||||||
return obeliskID;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void zeroOffset() {
|
|
||||||
offset = 0.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void lockOffset(boolean lock) {
|
|
||||||
lockOffset = lock;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
private double bearingAlign (LLResult llResult) {
|
|
||||||
double bearingOffset = 0.0;
|
|
||||||
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
|
|
||||||
final double MIN_OFFSET_POWER = 0.15;
|
|
||||||
final double TARGET_POSITION_TOLERANCE = 1.0;
|
|
||||||
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
|
||||||
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
|
||||||
final double DRIVE_POWER_REDUCTION = 2.0;
|
|
||||||
|
|
||||||
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
|
||||||
bearingAligned = true;
|
|
||||||
} else {
|
|
||||||
bearingAligned = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Only with valid data and if too far off target
|
|
||||||
if (llResult.isValid() && !bearingAligned)
|
|
||||||
{
|
|
||||||
|
|
||||||
// Adjust Robot Speed based on how far the target is located
|
|
||||||
// Only drive at half speed max
|
|
||||||
// switched to PID but original formula left for reference in comments
|
|
||||||
//drivePower = targetTx/HORIZONTAL_FOV_RANGE / DRIVE_POWER_REDUCTION;
|
|
||||||
bearingOffset = -(bearingPID.calculate(targetTx, 0.0));
|
|
||||||
|
|
||||||
// // Make sure we have enough power to actually drive the wheels
|
|
||||||
// if (abs(bearingOffset) < MIN_OFFSET_POWER) {
|
|
||||||
// if (bearingOffset > 0.0) {
|
|
||||||
// bearingOffset = MIN_OFFSET_POWER;
|
|
||||||
// } else {
|
|
||||||
// bearingOffset = -MIN_OFFSET_POWER;
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// }
|
|
||||||
}
|
|
||||||
|
|
||||||
return bearingOffset;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
public void trackGoal(Pose2d deltaPos) {
|
|
||||||
|
|
||||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
|
||||||
|
|
||||||
// Angle from robot to goal in robot frame
|
|
||||||
double desiredTurretAngleDeg = Math.toDegrees(
|
|
||||||
Math.atan2(deltaPos.position.y, deltaPos.position.x)
|
|
||||||
);
|
|
||||||
|
|
||||||
// Robot heading (field → robot)
|
|
||||||
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
|
|
||||||
|
|
||||||
// Turret angle needed relative to robot
|
|
||||||
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
|
||||||
turretAngleDeg = -turretAngleDeg;
|
|
||||||
|
|
||||||
// Normalize to [-180, 180]
|
|
||||||
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
|
||||||
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- LIMELIGHT VISION CORRECTION ---------------- */
|
|
||||||
// Update local limelight results
|
|
||||||
//double tagBearingDeg = getBearing(); // + = target is to the left
|
|
||||||
//boolean hasValidTarget = (tagBearingDeg != 1000.0);
|
|
||||||
|
|
||||||
turretAngleDeg += permanentOffset;
|
|
||||||
|
|
||||||
limelightRead();
|
|
||||||
// Active correction if we see the target
|
|
||||||
if (result.isValid() && !lockOffset) {
|
|
||||||
currentTrackOffset += bearingAlign(result);
|
|
||||||
currentTrackCount++;
|
|
||||||
// double bearingError = Math.abs(tagBearingDeg);
|
|
||||||
//
|
|
||||||
// if (bearingError > cameraBearingEqual) {
|
|
||||||
// // Apply sqrt scaling to reduce aggressive corrections at large errors
|
|
||||||
// double filteredBearing = Math.signum(tagBearingDeg) * Math.sqrt(Math.abs(tagBearingDeg));
|
|
||||||
//
|
|
||||||
// // Calculate correction
|
|
||||||
// double offsetChange = visionCorrectionGain * filteredBearing;
|
|
||||||
//
|
|
||||||
// // Limit rate of change to prevent jumps
|
|
||||||
// offsetChange = Math.max(-maxOffsetChangePerCycle,
|
|
||||||
// Math.min(maxOffsetChangePerCycle, offsetChange));
|
|
||||||
//
|
|
||||||
// // Accumulate the correction
|
|
||||||
// offset += offsetChange;
|
|
||||||
//
|
|
||||||
// TELE.addData("Bearing Error", tagBearingDeg);
|
|
||||||
// TELE.addData("Offset Change", offsetChange);
|
|
||||||
// TELE.addData("Total Offset", offset);
|
|
||||||
// } else {
|
|
||||||
// // When centered, lock in the learned offset
|
|
||||||
// permanentOffset = offset;
|
|
||||||
// offset = 0.0;
|
|
||||||
// }
|
|
||||||
} else {
|
|
||||||
// only store perma update after 20+ successful tracks
|
|
||||||
// this did not work good in testing; only current works best so far.
|
|
||||||
// if (currentTrackCount > 20) {
|
|
||||||
// offset = currentTrackOffset;
|
|
||||||
// }
|
|
||||||
currentTrackOffset = 0.0;
|
|
||||||
currentTrackCount = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Apply accumulated offset
|
|
||||||
turretAngleDeg += offset + currentTrackOffset;
|
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- ANGLE → SERVO POSITION ---------------- */
|
|
||||||
|
|
||||||
double targetTurretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
|
||||||
|
|
||||||
// Clamp to physical servo limits
|
|
||||||
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
|
|
||||||
|
|
||||||
// Interpolate towards target position
|
|
||||||
double currentPos = getTurrPos();
|
|
||||||
double turretPos = targetTurretPos;
|
|
||||||
|
|
||||||
if (targetTurretPos == turrMin) {
|
|
||||||
turretPos = turrMin;
|
|
||||||
} else if (targetTurretPos == turrMax) {
|
|
||||||
turretPos = turrMax;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Set servo positions
|
|
||||||
robot.turr1.setPosition(turretPos);
|
|
||||||
robot.turr2.setPosition(1.0 - turretPos);
|
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- TELEMETRY ---------------- */
|
|
||||||
|
|
||||||
TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
|
|
||||||
TELE.addData("Target Pos", "%.3f", targetTurretPos);
|
|
||||||
TELE.addData("Current Pos", "%.3f", currentPos);
|
|
||||||
TELE.addData("Commanded Pos", "%.3f", turretPos);
|
|
||||||
TELE.addData("LL Valid", result.isValid());
|
|
||||||
TELE.addData("LL getTx", result.getTx());
|
|
||||||
TELE.addData("LL Offset", offset);
|
|
||||||
//TELE.addData("Bearing Error", hasValidTarget ? String.format("%.2f", tagBearingDeg) : "NO TARGET");
|
|
||||||
TELE.addData("Learned Offset", "%.2f", offset);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -29,7 +29,7 @@ dependencies {
|
|||||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
||||||
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
||||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
||||||
implementation "com.acmerobotics.dashboard:dashboard:0.5.1" //FTC Dash
|
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
|
|||||||
@@ -25,9 +25,5 @@ allprojects {
|
|||||||
}
|
}
|
||||||
|
|
||||||
repositories {
|
repositories {
|
||||||
repositories {
|
mavenCentral()
|
||||||
mavenCentral()
|
|
||||||
google()
|
|
||||||
maven { url 'https://maven.pedropathing.com' }
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user