Compare commits
9 Commits
SpindexerU
...
8bc0b1043a
| Author | SHA1 | Date | |
|---|---|---|---|
| 8bc0b1043a | |||
| 7a50aa5065 | |||
| 486bde729d | |||
| 80f095cd57 | |||
| 0549902505 | |||
| cfb51cfa15 | |||
| 04372ec410 | |||
| e665ddf032 | |||
| b08fe5ada5 |
@@ -133,8 +133,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPosition(spinPID);
|
||||||
robot.spin2.setPower(-spinPID);
|
robot.spin2.setPosition(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -143,8 +143,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
if (servo.spinEqual(spindexer)){
|
||||||
robot.spin1.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -224,8 +224,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
if (!servo.spinEqual(position)){
|
||||||
double spinPID = servo.setSpinPos(position);
|
double spinPID = servo.setSpinPos(position);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPosition(spinPID);
|
||||||
robot.spin2.setPower(-spinPID);
|
robot.spin2.setPosition(-spinPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
@@ -259,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.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(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;
|
||||||
|
|||||||
@@ -31,8 +31,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
|
|||||||
|
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class AutoFar_V1 extends LinearOpMode {
|
public class AutoFar_V1 extends LinearOpMode {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
@@ -133,8 +132,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPosition(spinPID);
|
||||||
robot.spin2.setPower(-spinPID);
|
robot.spin2.setPosition(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -143,8 +142,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
if (servo.spinEqual(spindexer)){
|
||||||
robot.spin1.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -224,8 +223,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
|||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
if (!servo.spinEqual(position)){
|
||||||
double spinPID = servo.setSpinPos(position);
|
double spinPID = servo.setSpinPos(position);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPosition(spinPID);
|
||||||
robot.spin2.setPower(-spinPID);
|
robot.spin2.setPosition(-spinPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
@@ -259,8 +258,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.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(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;
|
||||||
|
|||||||
@@ -0,0 +1,872 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bHGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bShoot1Tangent;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bShootH;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bShootX;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bShootY;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bXGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bYGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bh1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bh2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bh2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bh2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bt2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bt2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bt2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bx1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bx2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bx2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.bx2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.by1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.by2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.by2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.by2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rHGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rShoot1Tangent;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rShootH;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rShootX;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rShootY;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rXGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rYGate;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rh1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rh2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rh2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rh2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rt2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rt2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rt2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rx1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rx2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rx2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.rx2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.ry1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.ry2a;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.ry2b;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.ry2c;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses_LT_Indexed.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.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.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;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
@Config
|
||||||
|
public class Auto_LT_Indexed 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 = 20.0;
|
||||||
|
public static double pickup2Speed = 20.0;
|
||||||
|
public static double pickup3Speed = 20.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;
|
||||||
|
|
||||||
|
List<Boolean> s1 = new ArrayList<>();
|
||||||
|
|
||||||
|
List<Boolean> s2 = new ArrayList<>();
|
||||||
|
List<Boolean> s3 = new ArrayList<>();
|
||||||
|
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;
|
||||||
|
|
||||||
|
// ---- OPEN GATE / MIDFIELD ----
|
||||||
|
private double x3, y3, h3, t3;
|
||||||
|
|
||||||
|
// ---- PICKUP 2 ----
|
||||||
|
private double x4a, y4a, h4a;
|
||||||
|
private double x4b, y4b, h4b;
|
||||||
|
|
||||||
|
// ---- PICKUP 3 ----
|
||||||
|
private double x5a, y5a, h5a;
|
||||||
|
private double x5b, y5b, h5b;
|
||||||
|
|
||||||
|
// ---- PARK ----
|
||||||
|
private double xPark, yPark, hPark;
|
||||||
|
|
||||||
|
public Action prepareShootIndexed(double time) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
boolean testColor = false;
|
||||||
|
|
||||||
|
int s1Green = 0;
|
||||||
|
int s2Green = 0;
|
||||||
|
int s3Green = 0;
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = System.currentTimeMillis();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if ((System.currentTimeMillis() - stamp) < (goToDetectTime)) { //0.25-0.4 ish???
|
||||||
|
robot.spin1.setPosition(colorDetectPos); //0.43
|
||||||
|
robot.spin2.setPosition(1 - colorDetectPos);
|
||||||
|
} else if ((System.currentTimeMillis() - stamp) < (colorSenseTime + goToDetectTime)) {
|
||||||
|
|
||||||
|
|
||||||
|
double green1 = robot.color1.getNormalizedColors().green;
|
||||||
|
double red1 = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP1 = green1 / (green1 + red1 + blue1);
|
||||||
|
|
||||||
|
|
||||||
|
if (gP1 >= color1Thresh) {
|
||||||
|
s1Green ++;
|
||||||
|
}
|
||||||
|
|
||||||
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
|
double red2 = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP2 = green2 / (green2 + red2 + blue2);
|
||||||
|
|
||||||
|
if (gP2 >= color2Thresh) {
|
||||||
|
s2Green ++;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
double green3 = robot.color3.getNormalizedColors().green;
|
||||||
|
double red3 = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP3 = green3 / (green3 + red3 + blue3);
|
||||||
|
|
||||||
|
if (gP3 >= color3Thresh) {
|
||||||
|
s3Green ++;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
testColor = true;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
double spindexPos;
|
||||||
|
if (motif == 21) {
|
||||||
|
spindexPos =
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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 pickup2 = null;
|
||||||
|
TrajectoryActionBuilder shoot2 = null;
|
||||||
|
TrajectoryActionBuilder pickup3 = null;
|
||||||
|
TrajectoryActionBuilder shoot3 = null;
|
||||||
|
TrajectoryActionBuilder openGate = null;
|
||||||
|
TrajectoryActionBuilder park = 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;
|
||||||
|
|
||||||
|
// ===== SHOOT POSE =====
|
||||||
|
xShoot = rShootX;
|
||||||
|
yShoot = rShootY;
|
||||||
|
hShoot = rShootH;
|
||||||
|
shoot1Tangent = rShoot1Tangent;
|
||||||
|
|
||||||
|
// ===== GATE =====
|
||||||
|
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;
|
||||||
|
|
||||||
|
// ===== SHOOT POSE =====
|
||||||
|
xShoot = bShootX;
|
||||||
|
yShoot = bShootY;
|
||||||
|
hShoot = bShootH;
|
||||||
|
shoot1Tangent = bShoot1Tangent;
|
||||||
|
|
||||||
|
// ===== GATE =====
|
||||||
|
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));
|
||||||
|
|
||||||
|
openGate = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
|
||||||
|
.setReversed(true)
|
||||||
|
.splineToConstantHeading(new Vector2d(x3, y3), t3);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(x3, y3, h2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x4a, y4a), h4a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(x4b, y4b), h4b,
|
||||||
|
new TranslationalVelConstraint(pickup2Speed));
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(x4b, y4b, h4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
||||||
|
|
||||||
|
pickup3 = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x5a, y5a), h5a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(x5b, y5b), h5b,
|
||||||
|
new TranslationalVelConstraint(pickup3Speed));
|
||||||
|
shoot3 = drive.actionBuilder(new Pose2d(x5b, y5b, h5b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
||||||
|
park = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xPark, yPark), hPark);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
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)
|
||||||
|
);
|
||||||
|
|
||||||
|
//WORKING SHOOT ALL for the preload
|
||||||
|
|
||||||
|
//Pickup first pile
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
manageFlywheel(
|
||||||
|
shootAllVelocity,
|
||||||
|
shootAllHood,
|
||||||
|
pickup1Time,
|
||||||
|
x2b,
|
||||||
|
y2b,
|
||||||
|
pickup1XTolerance,
|
||||||
|
pickup1YTolerance
|
||||||
|
),
|
||||||
|
intake(intake1Time),
|
||||||
|
detectObelisk(
|
||||||
|
obelisk1Time,
|
||||||
|
x2b,
|
||||||
|
y2c,
|
||||||
|
obelisk1XTolerance,
|
||||||
|
obelisk1YTolerance,
|
||||||
|
obeliskTurrPos
|
||||||
|
)
|
||||||
|
),
|
||||||
|
new ParallelAction(
|
||||||
|
openGate.build() //TODO: Add other managing stuff here
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
);
|
||||||
|
|
||||||
|
motif = turret.detectObelisk(); //Detect Obelisk if not alr
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
manageFlywheel(
|
||||||
|
shootAllVelocity,
|
||||||
|
shootAllHood,
|
||||||
|
shoot1Time,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501
|
||||||
|
),
|
||||||
|
shoot1.build(),
|
||||||
|
prepareShootIndexed(shoot1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
manageShooterAuto(
|
||||||
|
shootAllTime,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501
|
||||||
|
),
|
||||||
|
shootAllIndexed(shootAllTime, spindexerSpeedIncrease)
|
||||||
|
)
|
||||||
|
|
||||||
|
);
|
||||||
|
|
||||||
|
//Shoot from first pile
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,804 @@
|
|||||||
|
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_Unindexed 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)
|
||||||
|
)
|
||||||
|
|
||||||
|
);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -182,8 +182,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPosition(spinPID);
|
||||||
robot.spin2.setPower(-spinPID);
|
robot.spin2.setPosition(-spinPID);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -192,8 +192,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)) {
|
if (servo.spinEqual(spindexer)) {
|
||||||
robot.spin1.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
@@ -203,6 +203,7 @@ 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;
|
||||||
@@ -240,8 +241,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
|
||||||
robot.spin1.setPower(-spinPow);
|
robot.spin1.setPosition(-spinPow);
|
||||||
robot.spin2.setPower(spinPow);
|
robot.spin2.setPosition(spinPow);
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
@@ -271,12 +272,12 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (ticker % 12 < 6) {
|
if (ticker % 12 < 6) {
|
||||||
|
|
||||||
robot.spin1.setPower(-1);
|
robot.spin1.setPosition(-1);
|
||||||
robot.spin2.setPower(1);
|
robot.spin2.setPosition(1);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPower(1);
|
robot.spin1.setPosition(1);
|
||||||
robot.spin2.setPower(-1);
|
robot.spin2.setPosition(-1);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (getRuntime() - stamp > jamTime+0.4) {
|
if (getRuntime() - stamp > jamTime+0.4) {
|
||||||
@@ -317,20 +318,20 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (ticker % 60 < 12) {
|
if (ticker % 60 < 12) {
|
||||||
|
|
||||||
robot.spin1.setPower(-1);
|
robot.spin1.setPosition(-1);
|
||||||
robot.spin2.setPower(1);
|
robot.spin2.setPosition(1);
|
||||||
|
|
||||||
} else if (ticker % 60 < 30) {
|
} else if (ticker % 60 < 30) {
|
||||||
robot.spin1.setPower(-0.5);
|
robot.spin1.setPosition(-0.5);
|
||||||
robot.spin2.setPower(0.5);
|
robot.spin2.setPosition(0.5);
|
||||||
}
|
}
|
||||||
else if (ticker % 60 < 42) {
|
else if (ticker % 60 < 42) {
|
||||||
robot.spin1.setPower(1);
|
robot.spin1.setPosition(1);
|
||||||
robot.spin2.setPower(-1);
|
robot.spin2.setPosition(-1);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
robot.spin1.setPower(0.5);
|
robot.spin1.setPosition(0.5);
|
||||||
robot.spin2.setPower(-0.5);
|
robot.spin2.setPosition(-0.5);
|
||||||
}
|
}
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
TELE.addData("Reverse?", reverse);
|
TELE.addData("Reverse?", reverse);
|
||||||
@@ -338,11 +339,11 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (getRuntime() - stamp > intakeTime) {
|
if (getRuntime() - stamp > intakeTime) {
|
||||||
if (reverse) {
|
if (reverse) {
|
||||||
robot.spin1.setPower(-1);
|
robot.spin1.setPosition(-1);
|
||||||
robot.spin2.setPower(1);
|
robot.spin2.setPosition(1);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPower(1);
|
robot.spin1.setPosition(1);
|
||||||
robot.spin2.setPower(-1);
|
robot.spin2.setPosition(-1);
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -2,4 +2,5 @@ package org.firstinspires.ftc.teamcode.constants;
|
|||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,86 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class Poses_LT_Indexed {
|
||||||
|
|
||||||
|
// ================= FIELD / GOAL =================
|
||||||
|
public static double goalHeight = 42; // inches
|
||||||
|
public static double turretHeight = 12;
|
||||||
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
|
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
||||||
|
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
||||||
|
|
||||||
|
// =================================================
|
||||||
|
// ================= RED ALLIANCE ==================
|
||||||
|
// =================================================
|
||||||
|
|
||||||
|
// -------- FIRST SHOT --------
|
||||||
|
public static double rx1 = 20, ry1 = 0, rh1 = 0;
|
||||||
|
|
||||||
|
// -------- PICKUP 1 --------
|
||||||
|
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI / 2);
|
||||||
|
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI / 2);
|
||||||
|
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI / 2);
|
||||||
|
|
||||||
|
// -------- OPEN GATE --------
|
||||||
|
public static double rXGate = 30, rYGate = 63, rHGate = Math.toRadians(179);
|
||||||
|
|
||||||
|
// -------- PICKUP 2 --------
|
||||||
|
public static double rx3 = 0, ry3 = 0, rh3 = 0, rt3 = 0;
|
||||||
|
|
||||||
|
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
||||||
|
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
|
// -------- PICKUP 3 --------
|
||||||
|
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||||
|
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double rx5a = 0, ry5a = 0, rh5a = 0;
|
||||||
|
public static double rx5b = 0, ry5b = 0, rh5b = 0;
|
||||||
|
|
||||||
|
// -------- SHOOT --------
|
||||||
|
public static double rShootX = 40, rShootY = 7, rShootH = Math.toRadians(140);
|
||||||
|
public static double rShoot1Tangent = Math.toRadians(0);
|
||||||
|
|
||||||
|
// -------- PARK --------
|
||||||
|
public static double rXPark = 0, rYPark = 0, rHPark = 0;
|
||||||
|
|
||||||
|
// =================================================
|
||||||
|
// ================= BLUE ALLIANCE =================
|
||||||
|
// =================================================
|
||||||
|
|
||||||
|
// -------- FIRST SHOT --------
|
||||||
|
public static double bx1 = 20, by1 = 0, bh1 = 0;
|
||||||
|
|
||||||
|
// -------- PICKUP 1 --------
|
||||||
|
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
|
||||||
|
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
|
||||||
|
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
|
||||||
|
|
||||||
|
// -------- OPEN GATE --------
|
||||||
|
public static double bXGate = 25, bYGate = 69, bHGate = Math.toRadians(165);
|
||||||
|
|
||||||
|
// -------- PICKUP 2 --------
|
||||||
|
public static double bx3 = 0, by3 = 0, bh3 = 0, bt3 = 0;
|
||||||
|
|
||||||
|
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||||
|
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
// -------- PICKUP 3 --------
|
||||||
|
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||||
|
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx5a = 0, by5a = 0, bh5a = 0;
|
||||||
|
public static double bx5b = 0, by5b = 0, bh5b = 0;
|
||||||
|
|
||||||
|
// -------- SHOOT --------
|
||||||
|
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
|
||||||
|
public static double bShoot1Tangent = Math.toRadians(0);
|
||||||
|
|
||||||
|
// -------- PARK --------
|
||||||
|
public static double bXPark = 0, bYPark = 0, bHPark = 0;
|
||||||
|
}
|
||||||
@@ -0,0 +1,56 @@
|
|||||||
|
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,16 +5,18 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.18;
|
public static double spindexer_intakePos1 = 0;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.36;//0.5;
|
public static double spindexer_intakePos2 = 0.19;//0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.54;//0.66;
|
public static double spindexer_intakePos3 = 0.38;//0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.47;
|
public static double spindexer_outtakeBall3 = 0.65;
|
||||||
|
|
||||||
|
public static double spindexer_outtakeBall2 = 0.46;
|
||||||
|
public static double spindexer_outtakeBall1 = 0.27;
|
||||||
|
public static double spinStartPos = spindexer_outtakeBall1 - 0.08;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.31;
|
|
||||||
public static double spindexer_outtakeBall1 = 0.15;
|
|
||||||
|
|
||||||
public static double transferServo_out = 0.15;
|
public static double transferServo_out = 0.15;
|
||||||
|
|
||||||
|
|||||||
@@ -201,9 +201,9 @@ public final class MecanumDrive {
|
|||||||
public double kA = 0.000046;
|
public double kA = 0.000046;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// path profile parameters (in inches)
|
||||||
public double maxWheelVel = 180;
|
public double maxWheelVel = 250;
|
||||||
public double minProfileAccel = -40;
|
public double minProfileAccel = -40;
|
||||||
public double maxProfileAccel = 180;
|
public double maxProfileAccel = 250;
|
||||||
|
|
||||||
// turn profile parameters (in radians)
|
// turn profile parameters (in radians)
|
||||||
public double maxAngVel = 4 * Math.PI; // shared with path
|
public double maxAngVel = 4 * Math.PI; // shared with path
|
||||||
|
|||||||
@@ -162,11 +162,11 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
//TODO: make sure changing position works throughout opmode
|
//TODO: make sure changing position works throughout opmode
|
||||||
if (!servo.spinEqual(spindexPos)){
|
if (!servo.spinEqual(spindexPos)){
|
||||||
spindexPID = servo.setSpinPos(spindexPos);
|
spindexPID = servo.setSpinPos(spindexPos);
|
||||||
robot.spin1.setPower(spindexPID);
|
robot.spin1.setPosition(spindexPID);
|
||||||
robot.spin2.setPower(-spindexPID);
|
robot.spin2.setPosition(-spindexPID);
|
||||||
} else{
|
} else{
|
||||||
robot.spin1.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
//INTAKE:
|
//INTAKE:
|
||||||
|
|||||||
@@ -1,6 +1,7 @@
|
|||||||
package org.firstinspires.ftc.teamcode.teleop;
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
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.transferServo_out;
|
||||||
@@ -121,6 +122,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
private int tickerA = 1;
|
private int tickerA = 1;
|
||||||
private boolean transferIn = false;
|
private boolean transferIn = false;
|
||||||
boolean turretInterpolate = false;
|
boolean turretInterpolate = false;
|
||||||
|
public static double spinSpeedIncrease = 0.04;
|
||||||
|
|
||||||
public static double velPrediction(double distance) {
|
public static double velPrediction(double distance) {
|
||||||
if (distance < 30) {
|
if (distance < 30) {
|
||||||
@@ -139,13 +141,15 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
robot.light.setPosition(0);
|
||||||
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||||
|
|
||||||
for (LynxModule hub : allHubs) {
|
for (LynxModule hub : allHubs) {
|
||||||
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||||
}
|
}
|
||||||
|
|
||||||
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(hardwareMap);
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new Flywheel(hardwareMap);
|
||||||
@@ -167,14 +171,16 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// robot.limelight.start();
|
// robot.limelight.start();
|
||||||
|
|
||||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||||
waitForStart();
|
robot.light.setPosition(1);
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
|
// LIGHT COLORS
|
||||||
|
spindexer.ballCounterLight();
|
||||||
|
|
||||||
//DRIVETRAIN:
|
//DRIVETRAIN:
|
||||||
|
|
||||||
double y = 0.0;
|
double y = 0.0;
|
||||||
@@ -233,37 +239,43 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//TODO: Use color sensors to switch between positions...switch after ball detected in
|
//TODO: Use color sensors to switch between positions...switch after ball detected in
|
||||||
|
|
||||||
|
if (gamepad1.right_bumper){
|
||||||
|
shootAll = false;
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
if (autoSpintake) {
|
if (autoSpintake) {
|
||||||
|
|
||||||
if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) {
|
if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) {
|
||||||
spinCurrentPos = servo.getSpinPos();
|
|
||||||
|
|
||||||
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos);
|
|
||||||
|
|
||||||
robot.spin1.setPower(spindexPID);
|
robot.spin1.setPosition(spindexPos);
|
||||||
robot.spin2.setPower(-spindexPID);
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
|
|
||||||
|
shootAll = false;
|
||||||
|
|
||||||
intakeTicker++;
|
intakeTicker++;
|
||||||
|
|
||||||
if (intakeTicker % 20 < 2) {
|
// if (intakeTicker % 20 < 2) {
|
||||||
|
//
|
||||||
robot.spin1.setPower(-1);
|
// robot.spin1.setPower(-1);
|
||||||
robot.spin2.setPower(1);
|
// robot.spin2.setPower(1);
|
||||||
|
//
|
||||||
} else if (intakeTicker % 20 < 10) {
|
// } else if (intakeTicker % 20 < 10) {
|
||||||
robot.spin1.setPower(-0.5);
|
// robot.spin1.setPower(-0.5);
|
||||||
robot.spin2.setPower(0.5);
|
// robot.spin2.setPower(0.5);
|
||||||
} else if (intakeTicker % 20 < 12) {
|
// } else if (intakeTicker % 20 < 12) {
|
||||||
robot.spin1.setPower(1);
|
// robot.spin1.setPower(1);
|
||||||
robot.spin2.setPower(-1);
|
// robot.spin2.setPower(-1);
|
||||||
} else {
|
// } else {
|
||||||
robot.spin1.setPower(0.5);
|
// robot.spin1.setPower(0.5);
|
||||||
robot.spin2.setPower(-0.5);
|
// robot.spin2.setPower(-0.5);
|
||||||
}
|
// }
|
||||||
|
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
intakeStamp = getRuntime();
|
intakeStamp = getRuntime();
|
||||||
@@ -271,17 +283,9 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
} else {
|
} else {
|
||||||
if (!servo.spinEqual(spindexPos)) {
|
if (!servo.spinEqual(spindexPos)) {
|
||||||
spinCurrentPos = servo.getSpinPos();
|
robot.spin1.setPosition(spindexPos);
|
||||||
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
|
|
||||||
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos);
|
|
||||||
|
|
||||||
robot.spin1.setPower(spindexPID);
|
|
||||||
robot.spin2.setPower(-spindexPID);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
spindexPos = spindexer_intakePos1;
|
spindexPos = spindexer_intakePos1;
|
||||||
@@ -506,76 +510,76 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// }
|
// }
|
||||||
// }
|
// }
|
||||||
|
|
||||||
if (gamepad1.left_bumper && !enableSpindexerManager) {
|
//if (gamepad1.left_bumper && !enableSpindexerManager) {
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
// robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
autoSpintake = false;
|
// autoSpintake = false;
|
||||||
|
//
|
||||||
intakeTicker++;
|
// intakeTicker++;
|
||||||
|
//
|
||||||
if (intakeTicker % 10 < 1) {
|
// if (intakeTicker % 10 < 1) {
|
||||||
|
//
|
||||||
robot.spin1.setPower(-1);
|
// robot.spin1.setPower(-1);
|
||||||
robot.spin2.setPower(1);
|
// robot.spin2.setPower(1);
|
||||||
|
//
|
||||||
} else if (intakeTicker % 10 < 5) {
|
// } else if (intakeTicker % 10 < 5) {
|
||||||
robot.spin1.setPower(-0.5);
|
// robot.spin1.setPower(-0.5);
|
||||||
robot.spin2.setPower(0.5);
|
// robot.spin2.setPower(0.5);
|
||||||
} else if (intakeTicker % 10 < 6) {
|
// } else if (intakeTicker % 10 < 6) {
|
||||||
robot.spin1.setPower(1);
|
// robot.spin1.setPower(1);
|
||||||
robot.spin2.setPower(-1);
|
// robot.spin2.setPower(-1);
|
||||||
} else {
|
// } else {
|
||||||
robot.spin1.setPower(0.5);
|
// robot.spin1.setPower(0.5);
|
||||||
robot.spin2.setPower(-0.5);
|
// robot.spin2.setPower(-0.5);
|
||||||
}
|
// }
|
||||||
|
//
|
||||||
intake = false;
|
// intake = false;
|
||||||
reject = false;
|
// reject = false;
|
||||||
|
//
|
||||||
robot.intake.setPower(0.5);
|
// robot.intake.setPower(0.5);
|
||||||
|
//
|
||||||
}
|
// }
|
||||||
|
//
|
||||||
if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) {
|
// if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) {
|
||||||
shootStamp = getRuntime();
|
// shootStamp = getRuntime();
|
||||||
shootAll = true;
|
// shootAll = true;
|
||||||
|
//
|
||||||
shooterTicker = 0;
|
// shooterTicker = 0;
|
||||||
}
|
// }
|
||||||
|
//
|
||||||
if (shootAll && !enableSpindexerManager) {
|
// if (shootAll && !enableSpindexerManager) {
|
||||||
|
//
|
||||||
TELE.addData("100% works", shootOrder);
|
// TELE.addData("100% works", shootOrder);
|
||||||
|
//
|
||||||
intake = false;
|
// intake = false;
|
||||||
reject = false;
|
// reject = false;
|
||||||
|
//
|
||||||
shooterTicker++;
|
// shooterTicker++;
|
||||||
|
//
|
||||||
spindexPos = spindexer_intakePos1;
|
// spindexPos = spindexer_intakePos1;
|
||||||
|
//
|
||||||
if (getRuntime() - shootStamp < 3.5) {
|
// if (getRuntime() - shootStamp < 3.5) {
|
||||||
|
//
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
// robot.transferServo.setPosition(transferServo_in);
|
||||||
|
//
|
||||||
autoSpintake = false;
|
// autoSpintake = false;
|
||||||
|
//
|
||||||
robot.spin1.setPower(-spinPow);
|
// robot.spin1.setPower(-spinPow);
|
||||||
robot.spin2.setPower(spinPow);
|
// robot.spin2.setPower(spinPow);
|
||||||
|
//
|
||||||
} else {
|
// } else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
// robot.transferServo.setPosition(transferServo_out);
|
||||||
spindexPos = spindexer_intakePos1;
|
// spindexPos = spindexer_intakePos1;
|
||||||
|
//
|
||||||
shootAll = false;
|
// shootAll = false;
|
||||||
|
//
|
||||||
autoSpintake = true;
|
// autoSpintake = true;
|
||||||
|
//
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
// robot.transferServo.setPosition(transferServo_out);
|
||||||
}
|
// }
|
||||||
|
//
|
||||||
}
|
// }
|
||||||
|
|
||||||
if (enableSpindexerManager) {
|
if (enableSpindexerManager) {
|
||||||
if (!shootAll) {
|
if (!shootAll) {
|
||||||
@@ -599,6 +603,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
shootAll = true;
|
shootAll = true;
|
||||||
|
|
||||||
shooterTicker = 0;
|
shooterTicker = 0;
|
||||||
|
spindexPos = spinStartPos;// TODO: Change starting position based on desired order to shoot green ball
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (shootAll) {
|
if (shootAll) {
|
||||||
@@ -606,17 +612,18 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
intake = false;
|
intake = false;
|
||||||
reject = false;
|
reject = false;
|
||||||
|
|
||||||
shooterTicker++;
|
|
||||||
|
|
||||||
// TODO: Change starting position based on desired order to shoot green ball
|
|
||||||
spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
if (getRuntime() - shootStamp < 3.5) {
|
if (getRuntime() - shootStamp < 3.5) {
|
||||||
|
|
||||||
|
if (shooterTicker == 0 && !servo.spinEqual(spindexPos)){
|
||||||
|
robot.spin1.setPosition(spindexPos);
|
||||||
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
shooterTicker++;
|
||||||
robot.spin1.setPower(-spinPow);
|
double prevSpinPos = robot.spin1.getPosition();
|
||||||
robot.spin2.setPower(spinPow);
|
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
|
||||||
|
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
|
||||||
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
@@ -624,12 +631,19 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
shootAll = false;
|
shootAll = false;
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
spindexer.resetSpindexer();
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (gamepad1.left_stick_button){
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
//spindexPos = spindexer_intakePos1;
|
||||||
|
|
||||||
|
shootAll = false;
|
||||||
|
spindexer.resetSpindexer();
|
||||||
|
spindexer.processIntake();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|||||||
@@ -16,8 +16,7 @@ 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;
|
||||||
@@ -72,19 +71,19 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
initPos = currentPos;
|
initPos = currentPos;
|
||||||
}
|
}
|
||||||
if (reverse){
|
if (reverse){
|
||||||
robot.spin1.setPower(manualPow);
|
robot.spin1.setPosition(manualPow);
|
||||||
robot.spin2.setPower(-manualPow);
|
robot.spin2.setPosition(-manualPow);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPower(-manualPow);
|
robot.spin1.setPosition(-manualPow);
|
||||||
robot.spin2.setPower(manualPow);
|
robot.spin2.setPosition(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.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
|
|
||||||
if (getRuntime() - stamp < 1) {
|
if (getRuntime() - stamp < 1) {
|
||||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||||
@@ -191,15 +190,15 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
|
|
||||||
if (!atTarget) {
|
if (!atTarget) {
|
||||||
powPID = servo.setSpinPos(spindexerPos);
|
powPID = servo.setSpinPos(spindexerPos);
|
||||||
robot.spin1.setPower(powPID);
|
robot.spin1.setPosition(powPID);
|
||||||
robot.spin2.setPower(-powPID);
|
robot.spin2.setPosition(-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.setPower(0);
|
robot.spin1.setPosition(0);
|
||||||
robot.spin2.setPower(0);
|
robot.spin2.setPosition(0);
|
||||||
steadySpin = true;
|
steadySpin = true;
|
||||||
wasMoving = false;
|
wasMoving = false;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -17,7 +17,7 @@ public class LimelightTest extends LinearOpMode {
|
|||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Turret turret;
|
Turret turret;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
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 boolean turretMode = false;
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
|
|||||||
@@ -9,8 +9,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|||||||
|
|
||||||
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;
|
||||||
@@ -47,8 +45,8 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
|
|
||||||
double pid = controller.calculate(pos, target);
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
robot.spin1.setPower(pid);
|
robot.spin1.setPosition(pid);
|
||||||
robot.spin2.setPower(-pid);
|
robot.spin2.setPosition(-pid);
|
||||||
}
|
}
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
telemetry.addData("pos", pos);
|
||||||
|
|||||||
@@ -1,8 +1,11 @@
|
|||||||
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.spindexer_intakePos1;
|
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_in;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
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;
|
||||||
@@ -13,6 +16,7 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
|
|||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@@ -36,6 +40,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
public static boolean intake = false;
|
public static boolean intake = false;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
double shootStamp = 0.0;
|
double shootStamp = 0.0;
|
||||||
boolean shootAll = false;
|
boolean shootAll = false;
|
||||||
@@ -45,6 +50,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
public static boolean enableHoodAutoOpen = false;
|
public static boolean enableHoodAutoOpen = false;
|
||||||
public double hoodAdjust = 0.0;
|
public double hoodAdjust = 0.0;
|
||||||
public static double hoodAdjustFactor = 1.0;
|
public static double hoodAdjustFactor = 1.0;
|
||||||
|
private int shooterTicker = 0;
|
||||||
Spindexer spindexer ;
|
Spindexer spindexer ;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
@@ -55,6 +61,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new Flywheel(hardwareMap);
|
||||||
spindexer = new Spindexer(hardwareMap);
|
spindexer = new Spindexer(hardwareMap);
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -95,6 +102,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
shootAll = true;
|
shootAll = true;
|
||||||
shoot = false;
|
shoot = false;
|
||||||
robot.transfer.setPower(transferPower);
|
robot.transfer.setPower(transferPower);
|
||||||
|
shooterTicker = 0;
|
||||||
}
|
}
|
||||||
if (shootAll) {
|
if (shootAll) {
|
||||||
|
|
||||||
@@ -103,24 +111,31 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
|
|
||||||
// TODO: Change starting position based on desired order to shoot green ball
|
// TODO: Change starting position based on desired order to shoot green ball
|
||||||
//spindexPos = spindexer_intakePos1;
|
//spindexPos = spindexer_intakePos1;
|
||||||
|
|
||||||
if (getRuntime() - shootStamp < 3.5) {
|
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);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
robot.spin1.setPower(-spinPow);
|
|
||||||
robot.spin2.setPower(spinPow);
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
//spindexPos = spindexer_intakePos1;
|
//spindexPos = spindexer_intakePos1;
|
||||||
|
|
||||||
shootAll = false;
|
shootAll = false;
|
||||||
|
shooterTicker = 0;
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
robot.transfer.setPower(0);
|
robot.transfer.setPower(0);
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
spindexer.resetSpindexer();
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
|
|||||||
@@ -18,14 +18,10 @@ 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 int mode = 0; //0 for positional, 1 for power
|
public static double light = 0.501;
|
||||||
|
|
||||||
Turret turret;
|
Turret turret;
|
||||||
|
|
||||||
@@ -35,22 +31,13 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos(hardwareMap);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight );
|
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) && mode == 0){
|
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos)){
|
||||||
double pos = servo.setSpinPos(spindexPos);
|
robot.spin1.setPosition(spindexPos);
|
||||||
robot.spin1.setPower(pos);
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
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){
|
||||||
robot.turr1.setPosition(turretPos);
|
robot.turr1.setPosition(turretPos);
|
||||||
@@ -62,6 +49,9 @@ 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
|
||||||
@@ -79,7 +69,6 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
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("spindexer pow", robot.spin1.getPower());
|
|
||||||
TELE.addData("tpos ", turret.getTurrPos() );
|
TELE.addData("tpos ", turret.getTurrPos() );
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,6 +1,7 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
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;
|
||||||
@@ -40,8 +41,10 @@ public class Robot {
|
|||||||
public Servo transferServo;
|
public Servo transferServo;
|
||||||
public Servo turr1;
|
public Servo turr1;
|
||||||
public Servo turr2;
|
public Servo turr2;
|
||||||
public CRServo spin1;
|
|
||||||
public CRServo spin2;
|
public Servo spin1;
|
||||||
|
|
||||||
|
public Servo spin2;
|
||||||
public AnalogInput spin1Pos;
|
public AnalogInput spin1Pos;
|
||||||
public AnalogInput spin2Pos;
|
public AnalogInput spin2Pos;
|
||||||
public AnalogInput turr1Pos;
|
public AnalogInput turr1Pos;
|
||||||
@@ -52,6 +55,7 @@ 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 Robot(HardwareMap hardwareMap) {
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
@@ -93,17 +97,14 @@ public class Robot {
|
|||||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // 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(CRServo.class, "spin1");
|
spin1 = hardwareMap.get(Servo.class, "spin2");
|
||||||
|
|
||||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
spin2 = hardwareMap.get(Servo.class, "spin1");
|
||||||
|
|
||||||
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");
|
||||||
@@ -125,5 +126,7 @@ public class Robot {
|
|||||||
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");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -10,8 +10,8 @@ public class Servos {
|
|||||||
// TODO: get PIDF constants
|
// TODO: get PIDF constants
|
||||||
public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
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 turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||||
public static double spin_scalar = 1.0086;
|
public static double spin_scalar = 1.112;
|
||||||
public static double spin_restPos = 0.0;
|
public static double spin_restPos = 0.155;
|
||||||
public static double turret_scalar = 1.009;
|
public static double turret_scalar = 1.009;
|
||||||
public static double turret_restPos = 0.0;
|
public static double turret_restPos = 0.0;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
@@ -27,16 +27,14 @@ public class Servos {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// 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() {
|
||||||
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
||||||
}
|
}
|
||||||
|
|
||||||
//TODO: PID warp so 0 and 1 are usable positions
|
|
||||||
public double setSpinPos(double pos) {
|
public double setSpinPos(double pos) {
|
||||||
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
|
||||||
|
|
||||||
return spinPID.calculate(this.getSpinPos(), pos);
|
return pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
public boolean spinEqual(double pos) {
|
||||||
@@ -45,7 +43,6 @@ public class Servos {
|
|||||||
|
|
||||||
public double getTurrPos() {
|
public double getTurrPos() {
|
||||||
return 1.0;
|
return 1.0;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
public double setTurrPos(double pos) {
|
||||||
|
|||||||
@@ -4,6 +4,7 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
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_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
|
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_intakePos3;
|
||||||
@@ -67,7 +68,7 @@ public class Spindexer {
|
|||||||
SHOOTWAIT,
|
SHOOTWAIT,
|
||||||
SHOOT_ALL_PREP,
|
SHOOT_ALL_PREP,
|
||||||
SHOOT_ALL_READY
|
SHOOT_ALL_READY
|
||||||
};
|
}
|
||||||
|
|
||||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||||
public int unknownColorDetect = 0;
|
public int unknownColorDetect = 0;
|
||||||
@@ -75,7 +76,7 @@ public class Spindexer {
|
|||||||
UNKNOWN,
|
UNKNOWN,
|
||||||
GREEN,
|
GREEN,
|
||||||
PURPLE
|
PURPLE
|
||||||
};
|
}
|
||||||
|
|
||||||
class BallPosition {
|
class BallPosition {
|
||||||
boolean isEmpty = true;
|
boolean isEmpty = true;
|
||||||
@@ -247,17 +248,34 @@ public class Spindexer {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public void moveSpindexerToPos(double pos) {
|
public void moveSpindexerToPos(double pos) {
|
||||||
spinCurrentPos = servos.getSpinPos();
|
robot.spin1.setPosition(pos);
|
||||||
|
robot.spin2.setPosition(1-pos);
|
||||||
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
|
||||||
|
|
||||||
robot.spin1.setPower(spindexPID);
|
|
||||||
robot.spin2.setPower(-spindexPID);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public void stopSpindexer() {
|
public void stopSpindexer() {
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
}
|
||||||
|
|
||||||
|
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 isFull () {
|
public boolean isFull () {
|
||||||
@@ -305,33 +323,32 @@ public class Spindexer {
|
|||||||
// Find Next Open Position and start movement
|
// Find Next Open Position and start movement
|
||||||
double currentSpindexerPos = servos.getSpinPos();
|
double currentSpindexerPos = servos.getSpinPos();
|
||||||
double commandedtravelDistance = 2.0;
|
double commandedtravelDistance = 2.0;
|
||||||
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
//double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||||
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
//if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
if (ballPositions[0].isEmpty) {
|
||||||
// Position 1
|
// Position 1
|
||||||
commandedIntakePosition = 0;
|
commandedIntakePosition = 0;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
//proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||||
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
//if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
if (ballPositions[1].isEmpty) {
|
||||||
// Position 2
|
// Position 2
|
||||||
commandedIntakePosition = 1;
|
commandedIntakePosition = 1;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
//proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||||
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
if (ballPositions[2].isEmpty) {
|
||||||
// Position 3
|
// Position 3
|
||||||
commandedIntakePosition = 2;
|
commandedIntakePosition = 2;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||||
// Full
|
// Full
|
||||||
commandedIntakePosition = bestFitMotif();
|
//commandedIntakePosition = bestFitMotif();
|
||||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||||
}
|
}
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
|||||||
@@ -14,6 +14,8 @@ public class Targeting {
|
|||||||
double unitConversionFactor = 0.95;
|
double unitConversionFactor = 0.95;
|
||||||
|
|
||||||
int tileSize = 24; //inches
|
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 double robotInchesX, robotInchesY = 0.0;
|
||||||
|
|
||||||
@@ -100,6 +102,60 @@ public class Targeting {
|
|||||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
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 x1 = 0;
|
||||||
|
int y1 = 0;
|
||||||
|
// interpolate = false;
|
||||||
|
// if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
||||||
|
// (robotGridX < 5) && (robotGridY <5)) {
|
||||||
|
// // +X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
||||||
|
// (robotGridX > 0) && (robotGridY > 0)) {
|
||||||
|
// // -X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
||||||
|
// (robotGridX < 5) && (robotGridY > 0)) {
|
||||||
|
// // +X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
||||||
|
// (robotGridX > 0) && (robotGridY < 5)) {
|
||||||
|
// // -X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) {
|
||||||
|
// // -X, Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY;
|
||||||
|
// } else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) {
|
||||||
|
// // X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) {
|
||||||
|
// // +X, Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY;
|
||||||
|
// } else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) {
|
||||||
|
// // X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// }
|
||||||
|
|
||||||
//clamp
|
//clamp
|
||||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
@@ -115,9 +171,9 @@ public class Targeting {
|
|||||||
|
|
||||||
// bilinear interpolation
|
// bilinear interpolation
|
||||||
int x0 = robotGridX;
|
int x0 = robotGridX;
|
||||||
int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
//int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
||||||
int y0 = gridY;
|
int y0 = robotGridY;
|
||||||
int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
//int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
||||||
|
|
||||||
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
||||||
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
||||||
|
|||||||
@@ -1,12 +1,13 @@
|
|||||||
|
|
||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
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.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDController;
|
||||||
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.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
@@ -18,43 +19,43 @@ import java.util.List;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class Turret {
|
public class Turret {
|
||||||
|
|
||||||
public static double turretTolerance = 0.02;
|
public static double turretTolerance = 0.02;
|
||||||
public static double turrPosScalar = 0.00011264432;
|
public static double turrPosScalar = 0.00011264432;
|
||||||
public static double turret180Range = 0.4;
|
public static double turret180Range = 0.4;
|
||||||
public static double turrDefault = 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
|
// TODO: tune these values for limelight
|
||||||
// At the top with other static variables:
|
|
||||||
public static double kP = 0.015; // Proportional gain - tune this first
|
|
||||||
public static double kI = 0.0005; // Integral gain - add slowly if needed
|
|
||||||
public static double kD = 0.002; // Derivative gain - helps prevent overshoot
|
|
||||||
|
|
||||||
public static double kF = 0.002; // Derivative gain - helps prevent overshoot
|
public static double clampTolerance = 0.03;
|
||||||
|
|
||||||
public static double maxOffset = 10; // degrees - safety limit
|
|
||||||
|
|
||||||
// Add these as instance variables:
|
|
||||||
private double lastTagBearing = 0.0;
|
|
||||||
private double offsetIntegral = 0.0;
|
|
||||||
|
|
||||||
public static double cameraBearingEqual = 1;
|
|
||||||
|
|
||||||
|
|
||||||
public static double turrMin = 0.2;
|
|
||||||
public static double turrMax = 0.8;
|
|
||||||
public static double mult = 0.0;
|
|
||||||
private boolean lockOffset = false;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Limelight3A webcam;
|
Limelight3A webcam;
|
||||||
private int obeliskID = 0;
|
|
||||||
private double offset = 0.0;
|
|
||||||
|
|
||||||
private PIDFController controller = new PIDFController(kP, kI, kD, kF);
|
|
||||||
double tx = 0.0;
|
double tx = 0.0;
|
||||||
double ty = 0.0;
|
double ty = 0.0;
|
||||||
double limelightPosX = 0.0;
|
double limelightPosX = 0.0;
|
||||||
double limelightPosY = 0.0;
|
double limelightPosY = 0.0;
|
||||||
public static double clampTolerance = 0.03;
|
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) {
|
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||||
this.TELE = tele;
|
this.TELE = tele;
|
||||||
@@ -62,10 +63,11 @@ public class Turret {
|
|||||||
this.webcam = cam;
|
this.webcam = cam;
|
||||||
webcam.start();
|
webcam.start();
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
webcam.pipelineSwitch(3);
|
webcam.pipelineSwitch(4);
|
||||||
} else {
|
} else {
|
||||||
webcam.pipelineSwitch(2);
|
webcam.pipelineSwitch(2);
|
||||||
}
|
}
|
||||||
|
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
|
||||||
}
|
}
|
||||||
|
|
||||||
public void zeroTurretEncoder() {
|
public void zeroTurretEncoder() {
|
||||||
@@ -89,12 +91,12 @@ public class Turret {
|
|||||||
|
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
private void limelightRead() { // only for tracking purposes, not general reads
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
webcam.pipelineSwitch(3);
|
webcam.pipelineSwitch(4);
|
||||||
} else {
|
} else {
|
||||||
webcam.pipelineSwitch(2);
|
webcam.pipelineSwitch(2);
|
||||||
}
|
}
|
||||||
|
|
||||||
LLResult result = webcam.getLatestResult();
|
result = webcam.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
tx = result.getTx();
|
tx = result.getTx();
|
||||||
@@ -158,9 +160,50 @@ public class Turret {
|
|||||||
/*
|
/*
|
||||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
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) {
|
public void trackGoal(Pose2d deltaPos) {
|
||||||
|
|
||||||
controller.setPIDF(kP, kI, kD, kF);
|
|
||||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||||
|
|
||||||
// Angle from robot to goal in robot frame
|
// Angle from robot to goal in robot frame
|
||||||
@@ -173,55 +216,96 @@ public class Turret {
|
|||||||
|
|
||||||
// Turret angle needed relative to robot
|
// Turret angle needed relative to robot
|
||||||
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
||||||
|
|
||||||
turretAngleDeg = -turretAngleDeg;
|
turretAngleDeg = -turretAngleDeg;
|
||||||
|
|
||||||
// Normalize to [-180, 180]
|
// Normalize to [-180, 180]
|
||||||
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
||||||
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
||||||
|
|
||||||
/* ---------------- APRILTAG CORRECTION ---------------- */
|
|
||||||
|
/* ---------------- 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);
|
||||||
//
|
//
|
||||||
double tagBearingDeg = getBearing(); // + = target is to the left
|
// if (bearingError > cameraBearingEqual) {
|
||||||
|
// // Apply sqrt scaling to reduce aggressive corrections at large errors
|
||||||
turretAngleDeg += offset;
|
// double filteredBearing = Math.signum(tagBearingDeg) * Math.sqrt(Math.abs(tagBearingDeg));
|
||||||
|
//
|
||||||
/* ---------------- ANGLE → SERVO ---------------- */
|
// // Calculate correction
|
||||||
|
// double offsetChange = visionCorrectionGain * filteredBearing;
|
||||||
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
//
|
||||||
|
// // Limit rate of change to prevent jumps
|
||||||
// Clamp to servo range
|
// offsetChange = Math.max(-maxOffsetChangePerCycle,
|
||||||
double currentEncoderPos = this.getTurrPos();
|
// Math.min(maxOffsetChangePerCycle, offsetChange));
|
||||||
|
//
|
||||||
if (!turretEqual(turretPos)) {
|
// // Accumulate the correction
|
||||||
double diff = turretPos - currentEncoderPos;
|
// offset += offsetChange;
|
||||||
turretPos = turretPos + diff * mult;
|
//
|
||||||
|
// 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;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentEncoderPos < (turrMin + clampTolerance) || currentEncoderPos > (turrMax - clampTolerance)) {
|
// Apply accumulated offset
|
||||||
// Clamp to servo range
|
turretAngleDeg += offset + currentTrackOffset;
|
||||||
turretPos = Math.max(turrMin, Math.min(turretPos, turrMax));
|
|
||||||
} else { // TODO: add so it only adds error when standstill
|
|
||||||
if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) > cameraBearingEqual && !lockOffset) {
|
|
||||||
// PID-based offset correction for faster, smoother tracking
|
|
||||||
|
|
||||||
// Proportional: respond to current error
|
|
||||||
|
|
||||||
offset = -controller.calculate(tagBearingDeg);
|
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------------- 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.turr1.setPosition(turretPos);
|
||||||
robot.turr2.setPosition(1.0 - turretPos);
|
robot.turr2.setPosition(1.0 - turretPos);
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- TELEMETRY ---------------- */
|
/* ---------------- TELEMETRY ---------------- */
|
||||||
|
|
||||||
TELE.addData("Turret Angle", turretAngleDeg);
|
TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
|
||||||
TELE.addData("Bearing", tagBearingDeg);
|
TELE.addData("Target Pos", "%.3f", targetTurretPos);
|
||||||
TELE.addData("Offset", offset);
|
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -26,10 +26,10 @@ dependencies {
|
|||||||
|
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
||||||
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
||||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
||||||
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash
|
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user