Compare commits
4 Commits
edc300c1d5
...
danielv2
| Author | SHA1 | Date | |
|---|---|---|---|
| 28919e54a8 | |||
| 6dee088300 | |||
| ba251f8a46 | |||
| be14e719e9 |
@@ -1,4 +1,4 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
@@ -21,7 +21,6 @@ import com.acmerobotics.roadrunner.ftc.Actions;
|
|||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
@@ -32,7 +31,6 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
|
|||||||
|
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Disabled
|
|
||||||
@Config
|
@Config
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
public class AutoClose_V3 extends LinearOpMode {
|
public class AutoClose_V3 extends LinearOpMode {
|
||||||
@@ -54,7 +52,7 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
int b2 = 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
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
public static double holdTurrPow = 0.1; // power to hold turret in place
|
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
public Action initShooter(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
@@ -105,17 +103,17 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
if (gpp || pgp || ppg) {
|
if (gpp || pgp || ppg) {
|
||||||
if (redAlliance){
|
if (redAlliance){
|
||||||
robot.limelight.pipelineSwitch(3);
|
robot.limelight.pipelineSwitch(3);
|
||||||
double turretPID = turret_redClose;
|
double turretPID = servo.setTurrPos(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(-turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
return false;
|
return !servo.turretEqual(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
robot.limelight.pipelineSwitch(2);
|
||||||
double turretPID = turret_blueClose;
|
double turretPID = servo.setTurrPos(turret_blueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(-turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
return false;
|
return !servo.turretEqual(turret_blueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -134,9 +132,9 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
robot.spin2.setPosition(-spinPID);
|
robot.spin2.setPower(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -144,9 +142,9 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
if (servo.spinEqual(spindexer, robot.spin1Pos.getVoltage())){
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -190,8 +188,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
return true;
|
return true;
|
||||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
robot.turr1.setPosition(holdTurrPow);
|
robot.turr1.setPower(holdTurrPow);
|
||||||
robot.turr2.setPosition(holdTurrPow);
|
robot.turr2.setPower(holdTurrPow);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("shot once");
|
TELE.addLine("shot once");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -224,27 +222,27 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
if (!servo.spinEqual(position, robot.spin1Pos.getVoltage())){
|
||||||
double spinPID = servo.setSpinPos(position);
|
double spinPID = servo.setSpinPos(position, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
robot.spin2.setPosition(-spinPID);
|
robot.spin2.setPower(-spinPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
if (s1D < 43 && servo.spinEqual(position, robot.spin1Pos.getVoltage()) && getRuntime() - stamp > 0.5){
|
||||||
if (s2D > 60){
|
if (s2D > 60){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos2;
|
position = spindexer_intakePos2;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos3;
|
position = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos1;
|
position = spindexer_intakePos1;
|
||||||
}
|
}
|
||||||
} else if (s3D > 33){
|
} else if (s3D > 33){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos3;
|
position = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos1;
|
position = spindexer_intakePos1;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos2;
|
position = spindexer_intakePos2;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -261,8 +259,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
if (getRuntime() - stamp - intakeTime < 1){
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
return true;
|
return true;
|
||||||
@@ -413,7 +411,7 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
double turrPID;
|
double turrPID;
|
||||||
|
|
||||||
if (redAlliance){
|
if (redAlliance){
|
||||||
turrPID = turret_detectRedClose;
|
turrPID = servo.setTurrPos(turret_detectRedClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
@@ -432,7 +430,7 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
} else {
|
} else {
|
||||||
turrPID = turret_detectBlueClose;
|
turrPID = servo.setTurrPos(turret_detectBlueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
@@ -452,16 +450,16 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.turr1.setPosition(turrPID);
|
robot.turr1.setPower(turrPID);
|
||||||
robot.turr2.setPosition(-turrPID);
|
robot.turr2.setPower(-turrPID);
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
TELE.addData("Turret Pos", servo.getTurrPos(robot.turr1Pos.getCurrentPosition()));
|
||||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
TELE.addData("Spin Pos", servo.getSpinPos(robot.spin1Pos.getVoltage()));
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -567,10 +565,10 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
bearing = result.getTx();
|
bearing = result.getTx();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
double turretPos = servo.getTurrPos(robot.turr1Pos.getCurrentPosition()) - (bearing / 1300);
|
||||||
double turretPID = turretPos;
|
double turretPID = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(-turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
public void shootingSequence() {
|
public void shootingSequence() {
|
||||||
@@ -1,4 +1,4 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
@@ -21,7 +21,6 @@ import com.acmerobotics.roadrunner.ftc.Actions;
|
|||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
@@ -31,10 +30,9 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
|
|||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
@Disabled
|
|
||||||
@Config
|
|
||||||
@Autonomous
|
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
public class AutoFar_V1 extends LinearOpMode {
|
public class AutoFar_V1 extends LinearOpMode {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
@@ -54,7 +52,7 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
int b2 = 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
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
public static double holdTurrPow = 0.1; // power to hold turret in place
|
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
public Action initShooter(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
@@ -105,18 +103,18 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
if (gpp || pgp || ppg) {
|
if (gpp || pgp || ppg) {
|
||||||
if (redAlliance){
|
if (redAlliance){
|
||||||
robot.limelight.pipelineSwitch(3);
|
robot.limelight.pipelineSwitch(3);
|
||||||
robot.turr1.setPosition(turret_redFar);
|
double turretPID = servo.setTurrPos(turret_redFar, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr2.setPosition(-turret_redFar);
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turret_redFar, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
robot.limelight.pipelineSwitch(2);
|
||||||
|
double turretPID = servo.setTurrPos(turret_blueFar, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turret_blueFar);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(-turret_blueFar);
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turret_blueFar, robot.turr1Pos.getCurrentPosition());
|
||||||
}
|
}
|
||||||
|
|
||||||
return false;
|
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -134,9 +132,9 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
robot.spin2.setPosition(-spinPID);
|
robot.spin2.setPower(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -144,9 +142,9 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
if (servo.spinEqual(spindexer, robot.spin1Pos.getVoltage())){
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -190,8 +188,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
return true;
|
return true;
|
||||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
robot.turr1.setPosition(holdTurrPow);
|
robot.turr1.setPower(holdTurrPow);
|
||||||
robot.turr2.setPosition(holdTurrPow);
|
robot.turr2.setPower(holdTurrPow);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("shot once");
|
TELE.addLine("shot once");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -224,27 +222,27 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
if (!servo.spinEqual(position, robot.spin1Pos.getVoltage())){
|
||||||
double spinPID = servo.setSpinPos(position);
|
double spinPID = servo.setSpinPos(position, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
robot.spin2.setPosition(-spinPID);
|
robot.spin2.setPower(-spinPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
if (s1D < 43 && servo.spinEqual(position, robot.spin1Pos.getVoltage()) && getRuntime() - stamp > 0.5){
|
||||||
if (s2D > 60){
|
if (s2D > 60){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos2;
|
position = spindexer_intakePos2;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos3;
|
position = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos1;
|
position = spindexer_intakePos1;
|
||||||
}
|
}
|
||||||
} else if (s3D > 33){
|
} else if (s3D > 33){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos3;
|
position = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos1;
|
position = spindexer_intakePos1;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
position = spindexer_intakePos2;
|
position = spindexer_intakePos2;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -261,8 +259,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
if (getRuntime() - stamp - intakeTime < 1){
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
return true;
|
return true;
|
||||||
@@ -401,21 +399,21 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
double turrPID;
|
double turrPID;
|
||||||
|
|
||||||
if (redAlliance){
|
if (redAlliance){
|
||||||
turrPID = turret_detectRedClose;
|
turrPID = servo.setTurrPos(turret_detectRedClose, robot.turr1Pos.getCurrentPosition());
|
||||||
} else {
|
} else {
|
||||||
turrPID = turret_detectBlueClose;
|
turrPID = servo.setTurrPos(turret_detectBlueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.turr1.setPosition(turrPID);
|
robot.turr1.setPower(turrPID);
|
||||||
robot.turr2.setPosition(-turrPID);
|
robot.turr2.setPower(-turrPID);
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAutoFar);
|
robot.hood.setPosition(hoodAutoFar);
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
TELE.addData("Turret Pos", servo.getTurrPos(robot.turr1Pos.getCurrentPosition()));
|
||||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
TELE.addData("Spin Pos", servo.getSpinPos(robot.spin1Pos.getVoltage()));
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -468,10 +466,10 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
bearing = result.getTx();
|
bearing = result.getTx();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
double turretPos = servo.getTurrPos(robot.turr1Pos.getCurrentPosition()) - (bearing / 1300);
|
||||||
double turretPID = turretPos;
|
double turretPID = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(-turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
public void shootingSequence() {
|
public void shootingSequence() {
|
||||||
@@ -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);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -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,839 @@
|
|||||||
|
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.ServoPositions.hoodAuto;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||||
|
|
||||||
|
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.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;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||||
|
public class Blue_V2 extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTagWebcam aprilTag;
|
||||||
|
|
||||||
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
|
public static double intake1Time = 2.9;
|
||||||
|
|
||||||
|
public static double intake2Time = 2.9;
|
||||||
|
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
|
||||||
|
boolean gpp = false;
|
||||||
|
|
||||||
|
boolean pgp = false;
|
||||||
|
|
||||||
|
boolean ppg = false;
|
||||||
|
|
||||||
|
double powPID = 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
|
||||||
|
|
||||||
|
boolean spindexPosEqual(double spindexer) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex equal");
|
||||||
|
TELE.update();
|
||||||
|
return (scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01 &&
|
||||||
|
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double stamp2 = 0.0;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
targetVelocity = (double) vel;
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 16 == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||||
|
steady = true;
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished init");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action steadyShooter(int vel, boolean last) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
steady = flywheel.getSteady();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
|
||||||
|
if (last && !steady){
|
||||||
|
stamp = getRuntime();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
return false;
|
||||||
|
} else if (steady) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = getRuntime();
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (aprilTag.getTagById(21) != null) {
|
||||||
|
gpp = true;
|
||||||
|
} else if (aprilTag.getTagById(22) != null) {
|
||||||
|
pgp = true;
|
||||||
|
} else if (aprilTag.getTagById(23) != null) {
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
aprilTag.update();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg){
|
||||||
|
robot.turr1.setPower(turret_blueClose);
|
||||||
|
robot.turr2.setPower(1 - turret_blueClose);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intakeReject() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
double position = 0.0;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 0.3){
|
||||||
|
return true;
|
||||||
|
}else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex (double spindexer, double vel){
|
||||||
|
return new Action() {
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - 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));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.spin1.setPower(spindexer);
|
||||||
|
robot.spin2.setPower(1-spindexer);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
return !spindexPosEqual(spindexer);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(double vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - 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));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
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);
|
||||||
|
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 = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double position = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
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 < 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);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
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();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTagWebcam();
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
aprilTag.init(robot, TELE);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto-= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.turr1.setPower(turret_detectBlueClose);
|
||||||
|
robot.turr2.setPower(1 - turret_detectBlueClose);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
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(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
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(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
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,59 +1,9 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2a;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
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 androidx.annotation.NonNull;
|
||||||
|
|
||||||
@@ -66,52 +16,51 @@ import com.acmerobotics.roadrunner.ParallelAction;
|
|||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.acmerobotics.roadrunner.SequentialAction;
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
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.utils.Servos;
|
||||||
|
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
@Disabled
|
|
||||||
@Config
|
@Config
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
public class ProtoAutoClose_V3 extends LinearOpMode {
|
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;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
Flywheel flywheel;
|
FlywheelV2 flywheel;
|
||||||
Servos servo;
|
Servos servo;
|
||||||
|
|
||||||
double velo = 0.0;
|
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 gpp = false;
|
||||||
boolean pgp = false;
|
boolean pgp = false;
|
||||||
boolean ppg = false;
|
boolean ppg = false;
|
||||||
public static double spinUnjamTime = 0.6;
|
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
double bearing = 0.0;
|
double bearing = 0.0;
|
||||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
int b2 = 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
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
public Action initShooter(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
flywheel.manageFlywheel(vel);
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -124,7 +73,6 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
public Action Obelisk() {
|
public Action Obelisk() {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
int id = 0;
|
int id = 0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
@@ -138,11 +86,11 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (id == 21) {
|
if (id == 21){
|
||||||
gpp = true;
|
gpp = true;
|
||||||
} else if (id == 22) {
|
} else if (id == 22){
|
||||||
pgp = true;
|
pgp = true;
|
||||||
} else if (id == 23) {
|
} else if (id == 23){
|
||||||
ppg = true;
|
ppg = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -153,18 +101,19 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (gpp || pgp || ppg) {
|
if (gpp || pgp || ppg) {
|
||||||
if (redAlliance) {
|
if (redAlliance){
|
||||||
robot.limelight.pipelineSwitch(3);
|
robot.limelight.pipelineSwitch(3);
|
||||||
robot.turr1.setPosition(turret_redClose);
|
double turretPID = servo.setTurrPos(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr2.setPosition(1 - turret_redClose);
|
robot.turr1.setPower(turretPID);
|
||||||
return false;
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
robot.limelight.pipelineSwitch(2);
|
||||||
double turretPID = turret_blueClose;
|
double turretPID = servo.setTurrPos(turret_blueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(1 - turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
return false;
|
return !servo.turretEqual(turret_blueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -176,15 +125,16 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
public Action spindex(double spindexer, int vel) {
|
public Action spindex(double spindexer, int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
double spinPID = 0.0;
|
double spinPID = 0.0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
flywheel.manageFlywheel(vel);
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
robot.spin2.setPosition(-spinPID);
|
robot.spin2.setPower(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -192,10 +142,9 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)) {
|
if (servo.spinEqual(spindexer, robot.spin1Pos.getVoltage())){
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -204,7 +153,6 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public Action Shoot(int vel) {
|
public Action Shoot(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
int ticker = 1;
|
int ticker = 1;
|
||||||
@@ -214,7 +162,6 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
boolean zeroPassed = false;
|
boolean zeroPassed = false;
|
||||||
double currentPos = 0.0;
|
double currentPos = 0.0;
|
||||||
double prevPos = 0.0;
|
double prevPos = 0.0;
|
||||||
double stamp = 0.0;
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
@@ -222,82 +169,69 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
TELE.addLine("shooting");
|
TELE.addLine("shooting");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
robot.turr1.setPower(holdTurrPow);
|
||||||
|
robot.turr2.setPower(holdTurrPow);
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
robot.intake.setPower(-0.3);
|
if (ticker == 1){
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < 2.7) {
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
initPos = servo.getSpinPos(robot.spin1Pos.getVoltage());
|
||||||
|
|
||||||
robot.spin1.setPosition(-spinPow);
|
finalPos = initPos + 0.6;
|
||||||
robot.spin2.setPosition(spinPow);
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
if (finalPos > 1.0){
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
finalPos = finalPos - 1;
|
||||||
return false;
|
zeroNeeded = true;
|
||||||
|
} else if (finalPos > 0.95){
|
||||||
|
finalPos = 0.0;
|
||||||
|
zeroNeeded = true;
|
||||||
}
|
}
|
||||||
|
currentPos = initPos;
|
||||||
}
|
}
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action spindexUnjam(double jamTime) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
if (ticker == 1) {
|
if (ticker > 16){
|
||||||
stamp = getRuntime();
|
robot.spin1.setPower(0.08);
|
||||||
|
robot.spin2.setPower(-0.08);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ticker % 12 < 6) {
|
prevPos = currentPos;
|
||||||
|
currentPos = servo.getSpinPos(robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(-1);
|
if (zeroNeeded){
|
||||||
robot.spin2.setPosition(1);
|
if (currentPos - prevPos < -0.5){
|
||||||
|
zeroPassed = true;
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
}
|
||||||
|
if (zeroPassed){
|
||||||
if (getRuntime() - stamp > jamTime+0.4) {
|
if (currentPos > finalPos){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
robot.intake.setPower(0.5);
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
} else {
|
||||||
else if (getRuntime() - stamp > jamTime) {
|
|
||||||
|
|
||||||
robot.intake.setPower(-(getRuntime()-stamp-jamTime)*2.5);
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
else {
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
if (currentPos > finalPos){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
@@ -317,43 +251,37 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
if (ticker % 60 < 12) {
|
if (ticker % 12 < 3) {
|
||||||
|
|
||||||
robot.spin1.setPosition(-1);
|
robot.spin1.setPower(-1);
|
||||||
robot.spin2.setPosition(1);
|
robot.spin2.setPower(1);
|
||||||
|
|
||||||
} else if (ticker % 60 < 30) {
|
} else if (reverse) {
|
||||||
robot.spin1.setPosition(-0.5);
|
robot.spin1.setPower(1);
|
||||||
robot.spin2.setPosition(0.5);
|
robot.spin2.setPower(-1);
|
||||||
}
|
} else {
|
||||||
else if (ticker % 60 < 42) {
|
robot.spin1.setPower(-0.15);
|
||||||
robot.spin1.setPosition(1);
|
robot.spin2.setPower(0.15);
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
robot.spin1.setPosition(0.5);
|
|
||||||
robot.spin2.setPosition(-0.5);
|
|
||||||
}
|
}
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
TELE.addData("Reverse?", reverse);
|
TELE.addData("Reverse?", reverse);
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (getRuntime() - stamp > intakeTime) {
|
if (getRuntime() - stamp > intakeTime){
|
||||||
if (reverse) {
|
if (reverse){
|
||||||
robot.spin1.setPosition(-1);
|
robot.spin1.setPower(-1);
|
||||||
robot.spin2.setPosition(1);
|
robot.spin2.setPower(1);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPosition(1);
|
robot.spin1.setPower(1);
|
||||||
robot.spin2.setPosition(-1);
|
robot.spin2.setPower(-1);
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
if (ticker % 4 == 0) {
|
if (ticker % 4 == 0) {
|
||||||
spinCurrentPos = servo.getSpinPos();
|
spinCurrentPos = servo.getSpinPos(robot.spin1Pos.getVoltage());
|
||||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.02;
|
||||||
spinInitPos = spinCurrentPos;
|
spinInitPos = spinCurrentPos;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -364,7 +292,6 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
return new Action() {
|
return new Action() {
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
@@ -372,8 +299,10 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
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 s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
@@ -448,7 +377,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new FlywheelV2();
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(
|
TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -458,7 +387,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
0, 0, 0
|
0, 0, 0
|
||||||
));
|
));
|
||||||
|
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos();
|
||||||
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
robot.limelight.pipelineSwitch(1);
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
@@ -468,30 +397,18 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
.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))
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.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()) {
|
while (opModeInInit()) {
|
||||||
|
|
||||||
if (gamepad2.dpadUpWasPressed()) {
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
@@ -502,76 +419,54 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
hoodAuto += 0.01;
|
hoodAuto += 0.01;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
if (gamepad2.crossWasPressed()){
|
||||||
redAlliance = !redAlliance;
|
redAlliance = !redAlliance;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
double turretPID;
|
double turretPID;
|
||||||
if (redAlliance) {
|
if (redAlliance){
|
||||||
turretPID = turret_redClose;
|
turretPID = servo.setTurrPos(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b,
|
.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))
|
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b,
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.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 {
|
} else {
|
||||||
turretPID = turret_blueClose;
|
turretPID = servo.setTurrPos(turret_blueClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.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.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPosition(1 - turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
@@ -618,10 +513,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new SequentialAction(
|
new ParallelAction(
|
||||||
shoot1.build(),
|
shoot1.build()
|
||||||
spindexUnjam(spinUnjamTime)
|
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -651,36 +544,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new ParallelAction(
|
new ParallelAction(
|
||||||
shoot2.build(),
|
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)
|
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -703,7 +567,6 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//TODO: adjust this according to Teleop numbers
|
//TODO: adjust this according to Teleop numbers
|
||||||
public void detectTag() {
|
public void detectTag() {
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
@@ -712,9 +575,10 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
bearing = result.getTx();
|
bearing = result.getTx();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
double turretPos = (bearing / 1300);
|
double turretPos = servo.getTurrPos(robot.turr1Pos.getCurrentPosition()) - (bearing / 1300);
|
||||||
robot.turr1.setPosition(turretPos);
|
double turretPID = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr2.setPosition(1 - turretPos);
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
public void shootingSequence() {
|
public void shootingSequence() {
|
||||||
@@ -0,0 +1,771 @@
|
|||||||
|
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 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.SequentialAction;
|
||||||
|
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.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.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||||
|
public class Red_V2 extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTagWebcam aprilTag;
|
||||||
|
|
||||||
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.9;
|
||||||
|
|
||||||
|
public static double intake2Time = 2.9;
|
||||||
|
|
||||||
|
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 Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double stamp2 = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 16 == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||||
|
steady = true;
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished init");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action steadyShooter(int vel, boolean last) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
steady = flywheel.getSteady();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
if (last && !steady){
|
||||||
|
stamp = getRuntime();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
return false;
|
||||||
|
} else if (steady) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = getRuntime();
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (aprilTag.getTagById(21) != null) {
|
||||||
|
gpp = true;
|
||||||
|
} else if (aprilTag.getTagById(22) != null) {
|
||||||
|
pgp = true;
|
||||||
|
} else if (aprilTag.getTagById(23) != null) {
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
aprilTag.update();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg){
|
||||||
|
double turretPID = servo.setTurrPos(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turret_redClose, robot.turr1Pos.getCurrentPosition());
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex (double spindexer, int vel){
|
||||||
|
return new Action() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.spin1.setPower(spindexer);
|
||||||
|
robot.spin2.setPower(1-spindexer);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
return !servo.spinEqual(spindexer, robot.spin1Pos.getVoltage());
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
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());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
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);
|
||||||
|
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 = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intakeReject() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 0.3){
|
||||||
|
return true;
|
||||||
|
}else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double position = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
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 < 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);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
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();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTagWebcam();
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
aprilTag.init(robot, TELE);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto-= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos(robot.turr1Pos.getCurrentPosition()));
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
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(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
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(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void detectTag(){
|
||||||
|
AprilTagDetection d20 = aprilTag.getTagById(20);
|
||||||
|
AprilTagDetection d24 = aprilTag.getTagById(24);
|
||||||
|
|
||||||
|
if (d20 != null) {
|
||||||
|
bearing = d20.ftcPose.bearing;
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (d24 != null) {
|
||||||
|
bearing = d24.ftcPose.bearing;
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
}
|
||||||
|
double turretPos = servo.getTurrPos(robot.turr1Pos.getCurrentPosition()) - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -1,11 +1,5 @@
|
|||||||
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 boolean redAlliance = true;
|
||||||
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
|
|
||||||
|
|
||||||
public static double colorFilterAlpha = 0.15;
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,39 +12,22 @@ 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 Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0.5, rh1 = Math.toRadians(0.1);
|
public static double rx1 = 40, ry1 = -7, rh1 = 0;
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
||||||
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140.1);
|
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||||
|
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
||||||
|
public static double rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
|
public static double bx1 = 40, by1 = 6, bh1 = 0;
|
||||||
|
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
||||||
|
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||||
|
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||||
|
public static double bx3b = 34, by3b = -58, bh3b = 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 rx4a = 72, ry4a = 65, rh4a = Math.toRadians(145);
|
|
||||||
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 rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||||
|
|
||||||
public static double rShootX = 40, rShootY = -7, rShootH = Math.toRadians(50);
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
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,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);
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -5,22 +5,16 @@ 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.34;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.24; //0.33;//0.5;
|
public static double spindexer_intakePos2 = 0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.43; //0.53;//0.66;
|
public static double spindexer_intakePos3 = 0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
|
public static double spindexer_outtakeBall3 = 0.42;
|
||||||
public static double spindexer_outtakeBall3b = 0.15; //0.65; //0.24;
|
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
public static double spindexer_outtakeBall2 = 0.74;
|
||||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
public static double spindexer_outtakeBall1 = 0.58;
|
||||||
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;
|
||||||
|
|
||||||
@@ -30,7 +24,7 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double hoodDefault = 0.6;
|
public static double hoodDefault = 0.6;
|
||||||
|
|
||||||
public static double hoodAuto = 0.27;
|
public static double hoodAuto = 0.22;
|
||||||
|
|
||||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
public static double hoodAutoFar = 0.5; //TODO: change this;
|
||||||
|
|
||||||
@@ -46,10 +40,6 @@ public class ServoPositions {
|
|||||||
public static double turret_detectRedClose = 0.2;
|
public static double turret_detectRedClose = 0.2;
|
||||||
|
|
||||||
public static double turret_detectBlueClose = 0.6;
|
public static double turret_detectBlueClose = 0.6;
|
||||||
public static double turrDefault = 0.4;
|
public static double turrDefault = 0.40;
|
||||||
|
|
||||||
public static double turrMin = 0.2;
|
|
||||||
public static double turrMax = 0.8;
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -19,8 +19,6 @@ public class ShooterVars {
|
|||||||
public static double maxStep = 0.06; // prevents sudden jumps
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
|
||||||
// VELOCITY CONSTANTS
|
// VELOCITY CONSTANTS
|
||||||
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
public static int AUTO_CLOSE_VEL = 3000; //3300;
|
||||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
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 {
|
||||||
|
}
|
||||||
@@ -128,8 +128,8 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
TELE = new MultipleTelemetry(
|
TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
);
|
);
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos();
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new Flywheel();
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
@@ -158,15 +158,19 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
robot.frontRight.setPower(frontRightPower);
|
robot.frontRight.setPower(frontRightPower);
|
||||||
robot.backRight.setPower(backRightPower);
|
robot.backRight.setPower(backRightPower);
|
||||||
|
|
||||||
|
// PID SERVOS
|
||||||
|
turretPID = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
|
||||||
//TODO: make sure changing position works throughout opmode
|
//TODO: make sure changing position works throughout opmode
|
||||||
if (!servo.spinEqual(spindexPos)){
|
if (!servo.spinEqual(spindexPos, robot.spin1Pos.getVoltage())){
|
||||||
spindexPID = servo.setSpinPos(spindexPos);
|
spindexPID = servo.setSpinPos(spindexPos, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(spindexPID);
|
robot.spin1.setPower(spindexPID);
|
||||||
robot.spin2.setPosition(-spindexPID);
|
robot.spin2.setPower(-spindexPID);
|
||||||
} else{
|
} else{
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
//INTAKE:
|
//INTAKE:
|
||||||
@@ -282,7 +286,10 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
//SHOOTER:
|
//SHOOTER:
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel);
|
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
||||||
|
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
@@ -341,7 +348,7 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
bearing = d24.ftcPose.bearing;
|
bearing = d24.ftcPose.bearing;
|
||||||
}
|
}
|
||||||
overrideTurr = true;
|
overrideTurr = true;
|
||||||
turretPos = servo.getTurrPos() - (bearing/1300);
|
turretPos = servo.getTurrPos(robot.turr1Pos.getCurrentPosition()) - (bearing/1300);
|
||||||
TELE.addData("Bear", bearing);
|
TELE.addData("Bear", bearing);
|
||||||
|
|
||||||
double bearingCorrection = bearing / 1300;
|
double bearingCorrection = bearing / 1300;
|
||||||
@@ -474,13 +481,13 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
boolean shootingDone = false;
|
boolean shootingDone = false;
|
||||||
|
|
||||||
if (!outtake1) {
|
if (!outtake1) {
|
||||||
outtake1 = (servo.spinEqual(spindexer_outtakeBall1));
|
outtake1 = (servo.spinEqual(spindexer_outtakeBall1, robot.spin1Pos.getVoltage()));
|
||||||
}
|
}
|
||||||
if (!outtake2) {
|
if (!outtake2) {
|
||||||
outtake2 = (servo.spinEqual(spindexer_outtakeBall2));
|
outtake2 = (servo.spinEqual(spindexer_outtakeBall2, robot.spin1Pos.getVoltage()));
|
||||||
}
|
}
|
||||||
if (!outtake3) {
|
if (!outtake3) {
|
||||||
outtake3 = (servo.spinEqual(spindexer_outtakeBall3));
|
outtake3 = (servo.spinEqual(spindexer_outtakeBall3, robot.spin1Pos.getVoltage()));
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (currentSlot) {
|
switch (currentSlot) {
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -1,7 +1,5 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.colorFilterAlpha;
|
|
||||||
|
|
||||||
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;
|
||||||
@@ -20,9 +18,6 @@ public class ColorTest extends LinearOpMode {
|
|||||||
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());
|
||||||
double color1Distance = 0;
|
|
||||||
double color2Distance = 0;
|
|
||||||
double color3Distance = 0;
|
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
@@ -31,34 +26,28 @@ public class ColorTest extends LinearOpMode {
|
|||||||
double green1 = robot.color1.getNormalizedColors().green;
|
double green1 = robot.color1.getNormalizedColors().green;
|
||||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||||
double red1 = robot.color1.getNormalizedColors().red;
|
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 toColor", robot.color1.getNormalizedColors().toColor());
|
||||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||||
TELE.addData("Color1 distance (mm)", color1Distance);
|
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
// ----- COLOR 2 -----
|
// ----- COLOR 2 -----
|
||||||
double green2 = robot.color2.getNormalizedColors().green;
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
double red2 = robot.color2.getNormalizedColors().red;
|
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 toColor", robot.color2.getNormalizedColors().toColor());
|
||||||
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||||
TELE.addData("Color2 distance (mm)", color2Distance);
|
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
// ----- COLOR 3 -----
|
// ----- COLOR 3 -----
|
||||||
double green3 = robot.color3.getNormalizedColors().green;
|
double green3 = robot.color3.getNormalizedColors().green;
|
||||||
double blue3 = robot.color3.getNormalizedColors().blue;
|
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||||
double red3 = robot.color3.getNormalizedColors().red;
|
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 toColor", robot.color3.getNormalizedColors().toColor());
|
||||||
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||||
TELE.addData("Color3 distance (mm)", color3Distance);
|
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,7 +16,8 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
|
|||||||
import java.util.ArrayList;
|
import java.util.ArrayList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
public class IntakeTest extends LinearOpMode {
|
public class IntakeTest extends LinearOpMode {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
@@ -52,7 +53,7 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||||
}
|
}
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos();
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
@@ -64,26 +65,26 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
ticker++;
|
ticker++;
|
||||||
if (ticker % 16 == 0){
|
if (ticker % 16 == 0){
|
||||||
currentPos = servo.getSpinPos();
|
currentPos = servo.getSpinPos(robot.spin1Pos.getVoltage());
|
||||||
if (Math.abs(currentPos - initPos) == 0.0){
|
if (Math.abs(currentPos - initPos) == 0.0){
|
||||||
reverse = !reverse;
|
reverse = !reverse;
|
||||||
}
|
}
|
||||||
initPos = currentPos;
|
initPos = currentPos;
|
||||||
}
|
}
|
||||||
if (reverse){
|
if (reverse){
|
||||||
robot.spin1.setPosition(manualPow);
|
robot.spin1.setPower(manualPow);
|
||||||
robot.spin2.setPosition(-manualPow);
|
robot.spin2.setPower(-manualPow);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPosition(-manualPow);
|
robot.spin1.setPower(-manualPow);
|
||||||
robot.spin2.setPosition(manualPow);
|
robot.spin2.setPower(manualPow);
|
||||||
}
|
}
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
stamp = getRuntime();
|
stamp = getRuntime();
|
||||||
TELE.addData("Reverse?", reverse);
|
TELE.addData("Reverse?", reverse);
|
||||||
TELE.update();
|
TELE.update();
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
if (getRuntime() - stamp < 1) {
|
if (getRuntime() - stamp < 1) {
|
||||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||||
@@ -108,19 +109,19 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
|
|
||||||
if (ballIn(1) && steadySpin && intake && getRuntime() - stamp > 0.5){
|
if (ballIn(1) && steadySpin && intake && getRuntime() - stamp > 0.5){
|
||||||
if (!ballIn(2)){
|
if (!ballIn(2)){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos2;
|
spindexerPos = spindexer_intakePos2;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos3;
|
spindexerPos = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos1;
|
spindexerPos = spindexer_intakePos1;
|
||||||
}
|
}
|
||||||
} else if (!ballIn(3)){
|
} else if (!ballIn(3)){
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
if (servo.spinEqual(spindexer_intakePos1, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos3;
|
spindexerPos = spindexer_intakePos3;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
} else if (servo.spinEqual(spindexer_intakePos2, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos1;
|
spindexerPos = spindexer_intakePos1;
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
} else if (servo.spinEqual(spindexer_intakePos3, robot.spin1Pos.getVoltage())){
|
||||||
spindexerPos = spindexer_intakePos2;
|
spindexerPos = spindexer_intakePos2;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -157,7 +158,7 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
TELE.addData("B1", ballIn(1));
|
TELE.addData("B1", ballIn(1));
|
||||||
TELE.addData("B2", ballIn(2));
|
TELE.addData("B2", ballIn(2));
|
||||||
TELE.addData("B3", ballIn(3));
|
TELE.addData("B3", ballIn(3));
|
||||||
TELE.addData("Spindex Pos", servo.getSpinPos());
|
TELE.addData("Spindex Pos", servo.getSpinPos(robot.spin1Pos.getVoltage()));
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -186,19 +187,19 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public void spindexer() {
|
public void spindexer() {
|
||||||
boolean atTarget = servo.spinEqual(spindexerPos);
|
boolean atTarget = servo.spinEqual(spindexerPos, robot.spin1Pos.getVoltage());
|
||||||
|
|
||||||
if (!atTarget) {
|
if (!atTarget) {
|
||||||
powPID = servo.setSpinPos(spindexerPos);
|
powPID = servo.setSpinPos(spindexerPos, robot.spin1Pos.getVoltage());
|
||||||
robot.spin1.setPosition(powPID);
|
robot.spin1.setPower(powPID);
|
||||||
robot.spin2.setPosition(-powPID);
|
robot.spin2.setPower(-powPID);
|
||||||
|
|
||||||
steadySpin = false;
|
steadySpin = false;
|
||||||
wasMoving = true; // remember we were moving
|
wasMoving = true; // remember we were moving
|
||||||
stamp = getRuntime();
|
stamp = getRuntime();
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
steadySpin = true;
|
steadySpin = true;
|
||||||
wasMoving = false;
|
wasMoving = false;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -4,35 +4,32 @@ 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.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import java.util.List;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
//TODO: fix to get the apriltag that it is reading
|
//TODO: fix to get the apriltag that it is reading
|
||||||
public class LimelightTest extends LinearOpMode {
|
public class LimelightTest extends LinearOpMode {
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Turret turret;
|
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
||||||
Robot robot;
|
|
||||||
public static int 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 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
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
|
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "Limelight");
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
robot = new Robot(hardwareMap);
|
limelight.pipelineSwitch(pipeline);
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
robot.limelight.pipelineSwitch(pipeline);
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
limelight.start();
|
||||||
while (opModeIsActive()){
|
while (opModeIsActive()){
|
||||||
if (mode == 0){
|
if (mode == 0){
|
||||||
robot.limelight.pipelineSwitch(pipeline);
|
limelight.pipelineSwitch(pipeline);
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
LLResult result = limelight.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
TELE.addData("tx", result.getTx());
|
TELE.addData("tx", result.getTx());
|
||||||
@@ -41,29 +38,40 @@ public class LimelightTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else if (mode == 1){
|
} else if (mode == 1){
|
||||||
int obeliskID = turret.detectObelisk();
|
limelight.pipelineSwitch(1);
|
||||||
TELE.addData("Limelight ID", obeliskID);
|
LLResult result = limelight.getLatestResult();
|
||||||
|
if (result != null && result.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
int id = fiducial.getFiducialId();
|
||||||
|
TELE.addData("ID", id);
|
||||||
TELE.update();
|
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();
|
} else if (mode == 2){
|
||||||
double y = turret.getLimelightY();
|
limelight.pipelineSwitch(4);
|
||||||
TELE.addData("tx", tx);
|
LLResult result = limelight.getLatestResult();
|
||||||
TELE.addData("ty", ty);
|
if (result != null) {
|
||||||
TELE.addData("x", x);
|
if (result.isValid()) {
|
||||||
TELE.addData("y", y);
|
TELE.addData("tx", result.getTx());
|
||||||
|
TELE.addData("ty", result.getTy());
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else if (mode == 3){
|
||||||
|
limelight.pipelineSwitch(5);
|
||||||
|
LLResult result = limelight.getLatestResult();
|
||||||
|
if (result != null) {
|
||||||
|
if (result.isValid()) {
|
||||||
|
TELE.addData("tx", result.getTx());
|
||||||
|
TELE.addData("ty", result.getTy());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(0);
|
limelight.pipelineSwitch(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (turretMode){
|
|
||||||
if (turretPos != 0.501){
|
|
||||||
turret.manualSetTurret(turretPos);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -6,9 +6,13 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
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.CRServo;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
public class PIDServoTest extends LinearOpMode {
|
public class PIDServoTest extends LinearOpMode {
|
||||||
|
|
||||||
public static double p = 2, i = 0, d = 0, f = 0;
|
public static double p = 2, i = 0, d = 0, f = 0;
|
||||||
@@ -29,7 +33,7 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
|
|
||||||
PIDFController controller = new PIDFController(p, i, d, f);
|
PIDFController controller = new PIDFController(p, i, d, f);
|
||||||
|
|
||||||
controller.setTolerance(0.001);
|
controller.setTolerance(0);
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
@@ -40,16 +44,25 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
controller.setPIDF(p, i, d, f);
|
controller.setPIDF(p, i, d, f);
|
||||||
if (mode == 1) {
|
|
||||||
|
if (mode == 0) {
|
||||||
|
pos = robot.turr1Pos.getCurrentPosition();
|
||||||
|
|
||||||
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
|
robot.turr1.setPower(pid);
|
||||||
|
robot.turr2.setPower(-pid);
|
||||||
|
} else if (mode == 1) {
|
||||||
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
||||||
|
|
||||||
double pid = controller.calculate(pos, target);
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
robot.spin1.setPosition(pid);
|
robot.spin1.setPower(pid);
|
||||||
robot.spin2.setPosition(-pid);
|
robot.spin2.setPower(-pid);
|
||||||
}
|
}
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
telemetry.addData("pos", pos);
|
||||||
|
telemetry.addData("Turret Voltage", robot.turr1Pos.getCurrentPosition());
|
||||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
||||||
telemetry.addData("target", target);
|
telemetry.addData("target", target);
|
||||||
telemetry.addData("Mode", mode);
|
telemetry.addData("Mode", mode);
|
||||||
@@ -58,5 +71,4 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -1,11 +1,6 @@
|
|||||||
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;
|
||||||
@@ -14,44 +9,24 @@ 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.DcMotorEx;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
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.utils.Spindexer;
|
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
public class ShooterTest extends LinearOpMode {
|
public class ShooterTest extends LinearOpMode {
|
||||||
public static int mode = 1;
|
|
||||||
|
public static int mode = 0;
|
||||||
public static double parameter = 0.0;
|
public static double parameter = 0.0;
|
||||||
// --- CONSTANTS YOU TUNE ---
|
// --- CONSTANTS YOU TUNE ---
|
||||||
|
|
||||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||||
public static double Velocity = 0.0;
|
|
||||||
public static double P = 255.0;
|
|
||||||
public static double I = 0.0;
|
|
||||||
public static double D = 0.0;
|
|
||||||
public static double F = 7.5;
|
|
||||||
public static double transferPower = 1.0;
|
public static double transferPower = 1.0;
|
||||||
public static double hoodPos = 0.501;
|
public static double hoodPos = 0.501;
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
public static boolean shoot = false;
|
public static boolean shoot = false;
|
||||||
|
|
||||||
public static boolean intake = false;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
Flywheel flywheel;
|
FlywheelV2 flywheel;
|
||||||
Servos servo;
|
|
||||||
|
|
||||||
double shootStamp = 0.0;
|
|
||||||
boolean shootAll = false;
|
|
||||||
|
|
||||||
public double spinPow = 0.09;
|
|
||||||
|
|
||||||
public static boolean enableHoodAutoOpen = false;
|
|
||||||
public double hoodAdjust = 0.0;
|
|
||||||
public static double hoodAdjustFactor = 1.0;
|
|
||||||
private int shooterTicker = 0;
|
|
||||||
Spindexer spindexer ;
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -59,9 +34,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
DcMotorEx leftShooter = robot.shooter1;
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new FlywheelV2();
|
||||||
spindexer = new Spindexer(hardwareMap);
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -77,74 +50,28 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
rightShooter.setPower(parameter);
|
rightShooter.setPower(parameter);
|
||||||
leftShooter.setPower(parameter);
|
leftShooter.setPower(parameter);
|
||||||
} else if (mode == 1) {
|
} else if (mode == 1) {
|
||||||
flywheel.setPIDF(P, I, D, F);
|
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
flywheel.manageFlywheel((int) Velocity);
|
rightShooter.setPower(powPID);
|
||||||
|
leftShooter.setPower(powPID);
|
||||||
|
TELE.addData("PIDPower", powPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
if (enableHoodAutoOpen) {
|
|
||||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
|
||||||
} else {
|
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (turretPos != 0.501) {
|
||||||
|
robot.turr1.setPower(turretPos);
|
||||||
|
robot.turr2.setPower(turretPos);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (intake) {
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
if (shoot) {
|
|
||||||
shootStamp = getRuntime();
|
|
||||||
shootAll = true;
|
|
||||||
shoot = false;
|
|
||||||
robot.transfer.setPower(transferPower);
|
robot.transfer.setPower(transferPower);
|
||||||
shooterTicker = 0;
|
if (shoot) {
|
||||||
}
|
|
||||||
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);
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
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 {
|
TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()));
|
||||||
spindexer.processIntake();
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Velocity 1", flywheel.getVelo1());
|
TELE.addData("Velocity 1", flywheel.getVelo1());
|
||||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||||
TELE.addData("Power", robot.shooter1.getPower());
|
TELE.addData("Power", robot.shooter1.getPower());
|
||||||
|
|||||||
@@ -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,76 +1,88 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
|
||||||
public class Flywheel {
|
public class Flywheel {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double currentPos = 0.0;
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
public double velo1 = 0.0;
|
double velo1 = 0.0;
|
||||||
public double velo2 = 0.0;
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public Flywheel (HardwareMap hardwareMap) {
|
public Flywheel () {
|
||||||
robot = new Robot(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 () {
|
public double getVelo () {
|
||||||
return velo;
|
return velo;
|
||||||
}
|
}
|
||||||
public double getVelo1 () {
|
|
||||||
return velo1;
|
|
||||||
}
|
|
||||||
public double getVelo2 () {
|
|
||||||
return velo2;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean getSteady() {
|
public boolean getSteady() {
|
||||||
return steady;
|
return steady;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the robot PIDF for the next cycle.
|
private double getTimeSeconds ()
|
||||||
public void setPIDF(double p, double i, double d, double f) {
|
{
|
||||||
shooterPIDF1.p = p;
|
return (double) System.currentTimeMillis()/1000.0;
|
||||||
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
|
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
|
||||||
|
|
||||||
public double manageFlywheel(double commandedVelocity) {
|
|
||||||
targetVelocity = commandedVelocity;
|
targetVelocity = commandedVelocity;
|
||||||
|
|
||||||
// Add code here to set PIDF based on desired RPM
|
ticker++;
|
||||||
|
if (ticker % 2 == 0) {
|
||||||
|
velo5 = velo4;
|
||||||
|
velo4 = velo3;
|
||||||
|
velo3 = velo2;
|
||||||
|
velo2 = velo1;
|
||||||
|
|
||||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
currentPos = shooter1CurPos / 2048;
|
||||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
stamp = getTimeSeconds(); //getRuntime();
|
||||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
|
||||||
// Record Current Velocity
|
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
||||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
}
|
||||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
// Flywheel control code here
|
||||||
velo = Math.max(velo1,velo2);
|
if (targetVelocity - velo > 500) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - targetVelocity > 500){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else {
|
||||||
|
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- 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));
|
||||||
|
}
|
||||||
|
|
||||||
// really should be a running average of the last 5
|
// really should be a running average of the last 5
|
||||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||||
|
|
||||||
return powPID;
|
return powPID;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -73,18 +73,12 @@ public class FlywheelV2 {
|
|||||||
targetVelocity = commandedVelocity;
|
targetVelocity = commandedVelocity;
|
||||||
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
||||||
// Flywheel PID code here
|
// Flywheel PID code here
|
||||||
if (targetVelocity - velo > 4500) {
|
if (targetVelocity - velo > 500) {
|
||||||
powPID = 1.0;
|
powPID = 1.0;
|
||||||
} else if (velo - targetVelocity > 4500) {
|
} else if (velo - targetVelocity > 500) {
|
||||||
powPID = 0.0;
|
powPID = 0.0;
|
||||||
} else {
|
} else {
|
||||||
|
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||||
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 ---
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
double error = targetVelocity - velo;
|
double error = targetVelocity - velo;
|
||||||
|
|||||||
@@ -8,8 +8,6 @@ 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 {
|
||||||
@@ -18,30 +16,44 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
Servos servo;
|
Servos servo;
|
||||||
|
|
||||||
public static double spindexPos = 0.501;
|
public static double spindexPos = 0.501;
|
||||||
|
public static double spindexPow = 0.0;
|
||||||
|
public static double spinHoldPow = 0.0;
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
|
public static double turretPow = 0.0;
|
||||||
|
public static double turrHoldPow = 0.0;
|
||||||
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;
|
public static int mode = 0; //0 for positional, 1 for power
|
||||||
|
|
||||||
Turret turret;
|
|
||||||
|
|
||||||
@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);
|
servo = new Servos();
|
||||||
|
|
||||||
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 && !servo.spinEqual(spindexPos, robot.spin1Pos.getVoltage()) && mode == 0){
|
||||||
robot.spin1.setPosition(spindexPos);
|
double pos = servo.setSpinPos(spindexPos, robot.spin1Pos.getVoltage());
|
||||||
robot.spin2.setPosition(1-spindexPos);
|
robot.spin1.setPower(pos);
|
||||||
|
robot.spin2.setPower(-pos);
|
||||||
|
} else if (mode == 0){
|
||||||
|
robot.spin1.setPower(spinHoldPow);
|
||||||
|
robot.spin2.setPower(spinHoldPow);
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(spindexPow);
|
||||||
|
robot.spin2.setPower(-spindexPow);
|
||||||
}
|
}
|
||||||
if (turretPos != 0.501){
|
if (turretPos != 0.501 && !servo.turretEqual(turretPos, robot.turr1Pos.getCurrentPosition())){
|
||||||
robot.turr1.setPosition(turretPos);
|
double pos = servo.setTurrPos(turretPos, robot.turr1Pos.getCurrentPosition());
|
||||||
robot.turr2.setPosition(1-turretPos);
|
robot.turr1.setPower(pos);
|
||||||
|
robot.turr2.setPower(-pos);
|
||||||
|
} else if (mode == 0){
|
||||||
|
robot.turr1.setPower(turrHoldPow);
|
||||||
|
robot.turr2.setPower(turrHoldPow);
|
||||||
|
} else {
|
||||||
|
robot.turr1.setPower(turretPow);
|
||||||
|
robot.turr2.setPower(-turretPow);
|
||||||
}
|
}
|
||||||
if (transferPos != 0.501){
|
if (transferPos != 0.501){
|
||||||
robot.transferServo.setPosition(transferPos);
|
robot.transferServo.setPosition(transferPos);
|
||||||
@@ -49,9 +61,6 @@ 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){
|
|
||||||
robot.light.setPosition(light);
|
|
||||||
}
|
|
||||||
// To check configuration of spindexer:
|
// To check configuration of spindexer:
|
||||||
// Set "mode" to 1 and spindexPow to 0.1
|
// Set "mode" to 1 and spindexPow to 0.1
|
||||||
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
||||||
@@ -63,13 +72,14 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
// 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
|
// 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
|
//TODO: @KeshavAnandCode do the above please
|
||||||
|
|
||||||
TELE.addData("spindexer pos", servo.getSpinPos());
|
TELE.addData("spindexer pos", servo.getSpinPos(robot.spin1Pos.getVoltage()));
|
||||||
TELE.addData("turret pos", robot.turr1.getPosition());
|
TELE.addData("turret pos", servo.getTurrPos(robot.turr1Pos.getCurrentPosition()));
|
||||||
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
||||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||||
TELE.addData("hood pos", robot.hood.getPosition());
|
TELE.addData("hood pos", robot.hood.getPosition());
|
||||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||||
TELE.addData("tpos ", turret.getTurrPos() );
|
TELE.addData("turret voltage", robot.turr1Pos.getCurrentPosition());
|
||||||
|
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,7 +1,5 @@
|
|||||||
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.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;
|
||||||
@@ -10,44 +8,32 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
|||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
import 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.vision.apriltag.AprilTagProcessor;
|
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||||
|
|
||||||
@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 turr1;
|
public CRServo turr1;
|
||||||
public Servo turr2;
|
public CRServo turr2;
|
||||||
|
public CRServo spin1;
|
||||||
public Servo spin1;
|
public CRServo spin2;
|
||||||
|
|
||||||
public Servo spin2;
|
|
||||||
public AnalogInput spin1Pos;
|
public AnalogInput spin1Pos;
|
||||||
public AnalogInput spin2Pos;
|
public AnalogInput spin2Pos;
|
||||||
public AnalogInput turr1Pos;
|
public DcMotorEx turr1Pos;
|
||||||
public AnalogInput transferServoPos;
|
public AnalogInput transferServoPos;
|
||||||
public AprilTagProcessor aprilTagProcessor;
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
public WebcamName webcam;
|
public WebcamName webcam;
|
||||||
@@ -55,7 +41,10 @@ public class Robot {
|
|||||||
public RevColorSensorV3 color2;
|
public RevColorSensorV3 color2;
|
||||||
public RevColorSensorV3 color3;
|
public RevColorSensorV3 color3;
|
||||||
public Limelight3A limelight;
|
public Limelight3A limelight;
|
||||||
public Servo light;
|
|
||||||
|
public static boolean usingLimelight = true;
|
||||||
|
|
||||||
|
public static boolean usingCamera = true;
|
||||||
|
|
||||||
public Robot(HardwareMap hardwareMap) {
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
@@ -80,31 +69,29 @@ public class Robot {
|
|||||||
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
|
//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_WITHOUT_ENCODER);
|
||||||
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_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");
|
||||||
|
|
||||||
turr1 = hardwareMap.get(Servo.class, "t1");
|
turr1 = hardwareMap.get(CRServo.class, "t1");
|
||||||
|
|
||||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
turr2 = hardwareMap.get(CRServo.class, "t2");
|
||||||
|
|
||||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
turr1Pos = intake; // Encoder of turret plugged in intake port
|
||||||
|
|
||||||
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
||||||
spin1 = hardwareMap.get(Servo.class, "spin2");
|
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||||
|
|
||||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
spin2 = hardwareMap.get(Servo.class, "spin1");
|
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
||||||
|
|
||||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||||
|
|
||||||
|
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||||
|
|
||||||
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
||||||
@@ -120,13 +107,11 @@ public class Robot {
|
|||||||
|
|
||||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||||
|
|
||||||
if (usingLimelight) {
|
if (usingLimelight){
|
||||||
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
} else if (usingCamera) {
|
} else if (usingCamera){
|
||||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||||
}
|
}
|
||||||
|
|
||||||
light = hardwareMap.get(Servo.class, "light");
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -6,50 +6,54 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class Servos {
|
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;
|
Robot robot;
|
||||||
|
|
||||||
PIDFController spinPID;
|
PIDFController spinPID;
|
||||||
|
|
||||||
PIDFController turretPID;
|
PIDFController turretPID;
|
||||||
|
|
||||||
public Servos(HardwareMap hardwareMap) {
|
//PID constants
|
||||||
robot = new Robot(hardwareMap);
|
// TODO: get PIDF constants
|
||||||
|
public static double spinP = 3.4, spinI = 0, spinD = 0.075, spinF = 0.02;
|
||||||
|
public static double turrP = 4.0, turrI = 0.0, turrD = 0.0, turrF = 0.0;
|
||||||
|
|
||||||
|
public static double spin_scalar = 1.0086;
|
||||||
|
public static double spin_restPos = 0.0;
|
||||||
|
public static double turret_scalar = 1.009;
|
||||||
|
public static double turret_restPos = 0.0;
|
||||||
|
|
||||||
|
public Servos() {
|
||||||
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
turretPID.setTolerance(0.001);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// In the code below, encoder = robot.servo.getVoltage()
|
// In the code below, encoder = robot.servo.getVoltage()
|
||||||
// TODO: set the restPos and scalar
|
|
||||||
public double getSpinPos() {
|
public double getSpinPos(double voltage) {
|
||||||
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
return spin_scalar * ((voltage - spin_restPos) / 3.3);
|
||||||
|
}
|
||||||
|
//TODO: PID warp so 0 and 1 are usable positions
|
||||||
|
public double setSpinPos(double pos, double voltage) {
|
||||||
|
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
||||||
|
|
||||||
|
return spinPID.calculate(this.getSpinPos(voltage), pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setSpinPos(double pos) {
|
public boolean spinEqual(double pos, double voltage) {
|
||||||
|
return Math.abs(pos - this.getSpinPos(voltage)) < 0.02;
|
||||||
return pos;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
public double getTurrPos(double apos) {
|
||||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
return apos;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getTurrPos() {
|
public double setTurrPos(double pos, double apos) {
|
||||||
return 1.0;
|
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
|
return spinPID.calculate(this.getTurrPos(apos), pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
public boolean turretEqual(double pos, double apos) {
|
||||||
return 1.0;
|
return Math.abs(pos - this.getTurrPos(apos)) < 0.01;
|
||||||
}
|
|
||||||
|
|
||||||
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