Compare commits
77 Commits
7f3ca719fa
...
SpindexerU
| Author | SHA1 | Date | |
|---|---|---|---|
| d1434fbaa8 | |||
| d216ce78fc | |||
| 8dc03adfd3 | |||
| 7ffc51f60a | |||
| 7625f9a640 | |||
| fefeeb1f2e | |||
| b5a31afe52 | |||
| 8d29a80696 | |||
| 5922f4e935 | |||
| 78d38481a7 | |||
| 8a4bfecbf8 | |||
| 3591e20001 | |||
| 4050a354f7 | |||
| 16ffdd003f | |||
| f20e640c62 | |||
| c2e9d8fa87 | |||
| 46a5366a4a | |||
| fbdeb6e291 | |||
|
|
298b7bca8c | ||
| 2f0fcad128 | |||
| 45199b952b | |||
| 76ceb91fb7 | |||
| daccec4fdd | |||
| b55d44ae97 | |||
| 50212015e3 | |||
| c271c88e45 | |||
| 33300876ef | |||
| e1745500cc | |||
| 0dbf155608 | |||
| 313eeeaa95 | |||
| b28647373a | |||
| 7e7254aaea | |||
| e7dfa11196 | |||
| a3068cea2e | |||
| 51bf55cc49 | |||
| 6f3a178a08 | |||
| ccb52f625d | |||
| 8f92dc8f31 | |||
| 40d51ce757 | |||
| cfd09df8a0 | |||
| f1d4bb9d24 | |||
| 59796154bd | |||
| d42af20447 | |||
| 1c292e77c7 | |||
| fde0880225 | |||
| e8bf2033ad | |||
| de6e7f2910 | |||
| ef5d615f91 | |||
| 4aca64f61c | |||
| bfcecd42d3 | |||
| 66e76285b2 | |||
| 7b923f31ca | |||
| d3bbbb7f2b | |||
| c160b3fa6b | |||
| de52f86280 | |||
| 58e7289c7b | |||
| 46ed4f544f | |||
| e39fa396cb | |||
| 5e8727ebaa | |||
| c460a4fb7a | |||
| 301b5ec765 | |||
| 70ad084ab1 | |||
| 70ca5b814a | |||
| d81a189ef9 | |||
| 82c3c83262 | |||
| b9e6dff3f8 | |||
| 8e8629f624 | |||
| d967e0489d | |||
| 16d9a13376 | |||
| 1e87410d7b | |||
|
|
a7d1c18c56 | ||
| d5a3457be2 | |||
| 554204b6d4 | |||
| d586e3b4df | |||
| 2f5d4638ec | |||
| 1642e161c5 | |||
| 46a565c2c8 |
@@ -1,5 +1,6 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||
@@ -10,157 +11,88 @@ import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||
public class Red_V2 extends LinearOpMode {
|
||||
|
||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||
public class AutoClose_V3 extends LinearOpMode {
|
||||
Robot robot;
|
||||
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
MecanumDrive drive;
|
||||
|
||||
AprilTagWebcam aprilTag;
|
||||
|
||||
Flywheel flywheel;
|
||||
|
||||
FlywheelV2 flywheel;
|
||||
Servos servo;
|
||||
|
||||
double velo = 0.0;
|
||||
public static double intake1Time = 2.9;
|
||||
|
||||
public static double intake2Time = 2.9;
|
||||
|
||||
public static double intake1Time = 2.7;
|
||||
public static double intake2Time = 3.0;
|
||||
public static double colorDetect = 3.0;
|
||||
|
||||
boolean gpp = false;
|
||||
|
||||
boolean pgp = false;
|
||||
|
||||
boolean ppg = false;
|
||||
|
||||
double powPID = 0.0;
|
||||
|
||||
double bearing = 0.0;
|
||||
|
||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
public static double holdTurrPow = 0.1; // power to hold turret in place
|
||||
|
||||
public Action initShooter(int vel) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
double ticker = 0.0;
|
||||
double stamp2 = 0.0;
|
||||
boolean steady = false;
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp2 = getRuntime();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
if (ticker % 16 == 0) {
|
||||
stamp = getRuntime();
|
||||
stamp1 = stamp;
|
||||
}
|
||||
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||
steady = true;
|
||||
stamp2 = getRuntime();
|
||||
return true;
|
||||
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("finished init");
|
||||
TELE.update();
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action steadyShooter(int vel, boolean last) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
boolean steady = false;
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
steady = flywheel.getSteady();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
detectTag();
|
||||
|
||||
if (last && !steady){
|
||||
stamp = getRuntime();
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
return false;
|
||||
} else if (steady) {
|
||||
stamp = getRuntime();
|
||||
return true;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
return !flywheel.getSteady();
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Obelisk() {
|
||||
return new Action() {
|
||||
double stamp = getRuntime();
|
||||
int ticker = 0;
|
||||
|
||||
int id = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
id = fiducial.getFiducialId();
|
||||
TELE.addData("ID", id);
|
||||
TELE.update();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (aprilTag.getTagById(21) != null) {
|
||||
}
|
||||
|
||||
if (id == 21){
|
||||
gpp = true;
|
||||
} else if (aprilTag.getTagById(22) != null) {
|
||||
} else if (id == 22){
|
||||
pgp = true;
|
||||
} else if (aprilTag.getTagById(23) != null) {
|
||||
} else if (id == 23){
|
||||
ppg = true;
|
||||
}
|
||||
aprilTag.update();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("21", gpp);
|
||||
@@ -169,10 +101,20 @@ public class Red_V2 extends LinearOpMode {
|
||||
TELE.update();
|
||||
|
||||
if (gpp || pgp || ppg) {
|
||||
double turretPID = servo.setTurrPos(turret_red);
|
||||
robot.turr1.setPower(turretPID);
|
||||
robot.turr2.setPower(-turretPID);
|
||||
return !servo.turretEqual(turret_red);
|
||||
if (redAlliance){
|
||||
robot.limelight.pipelineSwitch(3);
|
||||
double turretPID = turret_redClose;
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(-turretPID);
|
||||
return false;
|
||||
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
double turretPID = turret_blueClose;
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(-turretPID);
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
@@ -182,24 +124,31 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
public Action spindex(double spindexer, int vel) {
|
||||
return new Action() {
|
||||
double spinPID = 0.0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.spin1.setPower(spindexer);
|
||||
robot.spin2.setPower(1-spindexer);
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
return !servo.spinEqual(spindexer);
|
||||
if (servo.spinEqual(spindexer)){
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
@@ -209,14 +158,15 @@ public class Red_V2 extends LinearOpMode {
|
||||
double transferStamp = 0.0;
|
||||
int ticker = 1;
|
||||
boolean transferIn = false;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shooting");
|
||||
TELE.update();
|
||||
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
@@ -238,6 +188,8 @@ public class Red_V2 extends LinearOpMode {
|
||||
return true;
|
||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
robot.turr1.setPosition(holdTurrPow);
|
||||
robot.turr2.setPosition(holdTurrPow);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shot once");
|
||||
TELE.update();
|
||||
@@ -252,9 +204,10 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double position = 0.0;
|
||||
double position = spindexer_intakePos1;
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
double pow = 1.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
@@ -263,17 +216,38 @@ public class Red_V2 extends LinearOpMode {
|
||||
}
|
||||
ticker++;
|
||||
|
||||
robot.intake.setPower(pow);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
if ((getRuntime() % 0.3) > 0.15) {
|
||||
position = spindexer_intakePos1 + 0.02;
|
||||
} else {
|
||||
position = spindexer_intakePos1 - 0.02;
|
||||
if (!servo.spinEqual(position)){
|
||||
double spinPID = servo.setSpinPos(position);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
}
|
||||
|
||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||
if (s2D > 60){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
position = spindexer_intakePos2;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
position = spindexer_intakePos3;
|
||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||
position = spindexer_intakePos1;
|
||||
}
|
||||
} else if (s3D > 33){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
position = spindexer_intakePos3;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
position = spindexer_intakePos1;
|
||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||
position = spindexer_intakePos2;
|
||||
}
|
||||
}
|
||||
stamp = getRuntime();
|
||||
}
|
||||
robot.spin1.setPower(position);
|
||||
robot.spin2.setPower(1 - position);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Intaking");
|
||||
@@ -284,41 +258,27 @@ public class Red_V2 extends LinearOpMode {
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(1);
|
||||
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intakeReject() {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (getRuntime() - stamp < 0.3){
|
||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
if (getRuntime() - stamp - intakeTime < 1){
|
||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||
return true;
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action ColorDetect() {
|
||||
public Action ColorDetect(int vel) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
double position = 0.0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
@@ -326,13 +286,10 @@ public class Red_V2 extends LinearOpMode {
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if ((getRuntime() % 0.3) > 0.15) {
|
||||
position = spindexer_intakePos1 + 0.02;
|
||||
} else {
|
||||
position = spindexer_intakePos1 - 0.02;
|
||||
}
|
||||
robot.spin1.setPower(position);
|
||||
robot.spin2.setPower(1 - position);
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
@@ -342,7 +299,7 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (s1D < 40) {
|
||||
if (s1D < 43) {
|
||||
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
@@ -350,8 +307,6 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b1 = 2;
|
||||
} else {
|
||||
@@ -359,7 +314,7 @@ public class Red_V2 extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
|
||||
if (s2D < 40) {
|
||||
if (s2D < 60) {
|
||||
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
@@ -374,7 +329,7 @@ public class Red_V2 extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
|
||||
if (s3D < 30) {
|
||||
if (s3D < 33) {
|
||||
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
@@ -409,7 +364,7 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new Flywheel();
|
||||
flywheel = new FlywheelV2();
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -419,28 +374,25 @@ public class Red_V2 extends LinearOpMode {
|
||||
0, 0, 0
|
||||
));
|
||||
|
||||
aprilTag = new AprilTagWebcam();
|
||||
robot.limelight.pipelineSwitch(1);
|
||||
robot.limelight.start();
|
||||
|
||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
aprilTag.init(robot, TELE);
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
@@ -452,28 +404,71 @@ public class Red_V2 extends LinearOpMode {
|
||||
hoodAuto += 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.crossWasPressed()){
|
||||
redAlliance = !redAlliance;
|
||||
}
|
||||
|
||||
double turrPID;
|
||||
|
||||
if (redAlliance){
|
||||
turrPID = turret_detectRedClose;
|
||||
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
} else {
|
||||
turrPID = turret_detectBlueClose;
|
||||
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turrPID);
|
||||
robot.turr2.setPosition(-turrPID);
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.spin1.setPower(spindexer_intakePos1);
|
||||
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||
|
||||
aprilTag.update();
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()) {
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
@@ -485,14 +480,11 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
@@ -511,9 +503,7 @@ public class Red_V2 extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot1.build(),
|
||||
ColorDetect(),
|
||||
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||
intakeReject()
|
||||
ColorDetect(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
|
||||
@@ -521,12 +511,12 @@ public class Red_V2 extends LinearOpMode {
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
@@ -544,20 +534,16 @@ public class Red_V2 extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot2.build(),
|
||||
ColorDetect(),
|
||||
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||
intakeReject()
|
||||
|
||||
ColorDetect(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
@@ -571,24 +557,18 @@ public class Red_V2 extends LinearOpMode {
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//TODO: adjust this according to Teleop numbers
|
||||
public void detectTag() {
|
||||
AprilTagDetection d20 = aprilTag.getTagById(20);
|
||||
AprilTagDetection d24 = aprilTag.getTagById(24);
|
||||
|
||||
if (d20 != null) {
|
||||
bearing = d20.ftcPose.bearing;
|
||||
TELE.addData("Bear", bearing);
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
bearing = result.getTx();
|
||||
}
|
||||
|
||||
if (d24 != null) {
|
||||
bearing = d24.ftcPose.bearing;
|
||||
TELE.addData("Bear", bearing);
|
||||
}
|
||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||
double turretPID = servo.setTurrPos(turretPos);
|
||||
robot.turr1.setPower(turretPID);
|
||||
robot.turr2.setPower(-turretPID);
|
||||
double turretPID = turretPos;
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(-turretPID);
|
||||
}
|
||||
|
||||
public void shootingSequence() {
|
||||
@@ -0,0 +1,651 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||
public class AutoFar_V1 extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
FlywheelV2 flywheel;
|
||||
Servos servo;
|
||||
|
||||
double velo = 0.0;
|
||||
public static double intake1Time = 2.7;
|
||||
public static double intake2Time = 3.0;
|
||||
public static double colorDetect = 3.0;
|
||||
boolean gpp = false;
|
||||
boolean pgp = false;
|
||||
boolean ppg = false;
|
||||
double powPID = 0.0;
|
||||
double bearing = 0.0;
|
||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
public static double holdTurrPow = 0.1; // power to hold turret in place
|
||||
|
||||
public Action initShooter(int vel) {
|
||||
return new Action() {
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
|
||||
return !flywheel.getSteady();
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Obelisk() {
|
||||
return new Action() {
|
||||
int id = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
id = fiducial.getFiducialId();
|
||||
TELE.addData("ID", id);
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (id == 21){
|
||||
gpp = true;
|
||||
} else if (id == 22){
|
||||
pgp = true;
|
||||
} else if (id == 23){
|
||||
ppg = true;
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("21", gpp);
|
||||
TELE.addData("22", pgp);
|
||||
TELE.addData("23", ppg);
|
||||
TELE.update();
|
||||
|
||||
if (gpp || pgp || ppg) {
|
||||
if (redAlliance){
|
||||
robot.limelight.pipelineSwitch(3);
|
||||
robot.turr1.setPosition(turret_redFar);
|
||||
robot.turr2.setPosition(-turret_redFar);
|
||||
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
|
||||
robot.turr1.setPosition(turret_blueFar);
|
||||
robot.turr2.setPosition(-turret_blueFar);
|
||||
|
||||
}
|
||||
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action spindex(double spindexer, int vel) {
|
||||
return new Action() {
|
||||
double spinPID = 0.0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (servo.spinEqual(spindexer)){
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Shoot(int vel) {
|
||||
return new Action() {
|
||||
double transferStamp = 0.0;
|
||||
int ticker = 1;
|
||||
boolean transferIn = false;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shooting");
|
||||
TELE.update();
|
||||
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
detectTag();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 1) {
|
||||
transferStamp = getRuntime();
|
||||
ticker++;
|
||||
}
|
||||
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("ticker", ticker);
|
||||
TELE.update();
|
||||
transferIn = true;
|
||||
return true;
|
||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
robot.turr1.setPosition(holdTurrPow);
|
||||
robot.turr2.setPosition(holdTurrPow);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shot once");
|
||||
TELE.update();
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double position = spindexer_intakePos1;
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
double pow = 1.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
robot.intake.setPower(pow);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
if (!servo.spinEqual(position)){
|
||||
double spinPID = servo.setSpinPos(position);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
}
|
||||
|
||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||
if (s2D > 60){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
position = spindexer_intakePos2;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
position = spindexer_intakePos3;
|
||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||
position = spindexer_intakePos1;
|
||||
}
|
||||
} else if (s3D > 33){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
position = spindexer_intakePos3;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
position = spindexer_intakePos1;
|
||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||
position = spindexer_intakePos2;
|
||||
}
|
||||
}
|
||||
stamp = getRuntime();
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Intaking");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(1);
|
||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
if (getRuntime() - stamp - intakeTime < 1){
|
||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||
return true;
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action ColorDetect(int vel) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (s1D < 43) {
|
||||
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b1 = 2;
|
||||
} else {
|
||||
b1 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s2D < 60) {
|
||||
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b2 = 2;
|
||||
} else {
|
||||
b2 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s3D < 33) {
|
||||
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b3 = 2;
|
||||
} else {
|
||||
b3 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Detecting");
|
||||
TELE.addData("Distance 1", s1D);
|
||||
TELE.addData("Distance 2", s2D);
|
||||
TELE.addData("Distance 3", s3D);
|
||||
TELE.addData("B1", b1);
|
||||
TELE.addData("B2", b2);
|
||||
TELE.addData("B3", b3);
|
||||
TELE.update();
|
||||
|
||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new FlywheelV2();
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||
0, 0, 0
|
||||
));
|
||||
|
||||
robot.limelight.pipelineSwitch(1);
|
||||
robot.limelight.start();
|
||||
|
||||
//TODO: add positions to develop auto
|
||||
|
||||
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(0,0,0))
|
||||
.strafeToLinearHeading(new Vector2d(rfx1, rfy1), rfh1);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
if (gamepad2.dpadUpWasPressed()) {
|
||||
hoodAuto -= 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.dpadDownWasPressed()) {
|
||||
hoodAuto += 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.crossWasPressed()){
|
||||
redAlliance = !redAlliance;
|
||||
}
|
||||
|
||||
double turrPID;
|
||||
|
||||
if (redAlliance){
|
||||
turrPID = turret_detectRedClose;
|
||||
} else {
|
||||
turrPID = turret_detectBlueClose;
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turrPID);
|
||||
robot.turr2.setPosition(-turrPID);
|
||||
|
||||
robot.hood.setPosition(hoodAutoFar);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()) {
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
initShooter(AUTO_FAR_VEL),
|
||||
Obelisk()
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(park.build());
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("finished");
|
||||
TELE.update();
|
||||
|
||||
sleep(2000);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
//TODO: adjust this according to Teleop numbers
|
||||
public void detectTag() {
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
bearing = result.getTx();
|
||||
}
|
||||
}
|
||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||
double turretPID = turretPos;
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(-turretPID);
|
||||
}
|
||||
|
||||
public void shootingSequence() {
|
||||
TELE.addData("Velocity", velo);
|
||||
if (gpp) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b2 == 2) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b3 == 2) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
}
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (pgp) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence4();
|
||||
TELE.addLine("sequence4");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b2 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b3 == 2) {
|
||||
sequence4();
|
||||
TELE.addLine("sequence4");
|
||||
}
|
||||
} else {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
}
|
||||
} else if (ppg) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence5();
|
||||
TELE.addLine("sequence5");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else if (b2 == 2) {
|
||||
sequence5();
|
||||
TELE.addLine("sequence5");
|
||||
} else if (b3 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
}
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
public void sequence1() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence2() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence3() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence4() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence5() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence6() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||
Shoot(AUTO_FAR_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -1,839 +0,0 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@Config
|
||||
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||
public class Blue_V2 extends LinearOpMode {
|
||||
|
||||
Robot robot;
|
||||
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
MecanumDrive drive;
|
||||
|
||||
AprilTagWebcam aprilTag;
|
||||
|
||||
Flywheel flywheel;
|
||||
|
||||
double velo = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
public static double intake1Time = 2.9;
|
||||
|
||||
public static double intake2Time = 2.9;
|
||||
|
||||
public static double colorDetect = 3.0;
|
||||
|
||||
boolean gpp = false;
|
||||
|
||||
boolean pgp = false;
|
||||
|
||||
boolean ppg = false;
|
||||
|
||||
double powPID = 0.0;
|
||||
|
||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
boolean spindexPosEqual(double spindexer) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex equal");
|
||||
TELE.update();
|
||||
return (scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01 &&
|
||||
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||
}
|
||||
|
||||
public Action initShooter(int vel) {
|
||||
return new Action() {
|
||||
double initPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
double ticker = 0.0;
|
||||
double stamp2 = 0.0;
|
||||
double currentPos = 0.0;
|
||||
boolean steady = false;
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp2 = getRuntime();
|
||||
}
|
||||
|
||||
targetVelocity = (double) vel;
|
||||
ticker++;
|
||||
if (ticker % 16 == 0) {
|
||||
stamp = getRuntime();
|
||||
stamp1 = stamp;
|
||||
}
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||
steady = true;
|
||||
stamp2 = getRuntime();
|
||||
return true;
|
||||
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("finished init");
|
||||
TELE.update();
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action steadyShooter(int vel, boolean last) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
boolean steady = false;
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
steady = flywheel.getSteady();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
|
||||
|
||||
if (last && !steady){
|
||||
stamp = getRuntime();
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
return false;
|
||||
} else if (steady) {
|
||||
stamp = getRuntime();
|
||||
return true;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Obelisk() {
|
||||
return new Action() {
|
||||
double stamp = getRuntime();
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (aprilTag.getTagById(21) != null) {
|
||||
gpp = true;
|
||||
} else if (aprilTag.getTagById(22) != null) {
|
||||
pgp = true;
|
||||
} else if (aprilTag.getTagById(23) != null) {
|
||||
ppg = true;
|
||||
}
|
||||
aprilTag.update();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("21", gpp);
|
||||
TELE.addData("22", pgp);
|
||||
TELE.addData("23", ppg);
|
||||
TELE.update();
|
||||
|
||||
if (gpp || pgp || ppg){
|
||||
robot.turr1.setPower(turret_blue);
|
||||
robot.turr2.setPower(1 - turret_blue);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intakeReject() {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
double position = 0.0;
|
||||
|
||||
if ((getRuntime() % 0.3) > 0.15) {
|
||||
position = spindexer_intakePos1 + 0.02;
|
||||
} else {
|
||||
position = spindexer_intakePos1 - 0.02;
|
||||
}
|
||||
|
||||
robot.spin1.setPower(position);
|
||||
robot.spin2.setPower(1 - position);
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (getRuntime() - stamp < 0.3){
|
||||
return true;
|
||||
}else {
|
||||
robot.intake.setPower(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action spindex (double spindexer, double vel){
|
||||
return new Action() {
|
||||
double currentPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
double initPos = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
int ticker = 0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
ticker++;
|
||||
if (ticker % 8 == 0) {
|
||||
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||
stamp = getRuntime();
|
||||
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||
initPos = currentPos;
|
||||
stamp1 = stamp;
|
||||
}
|
||||
|
||||
if (vel - velo > 500 && ticker > 16) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - vel > 500 && ticker > 16){
|
||||
powPID = 0.0;
|
||||
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = vel - velo;
|
||||
double correction = kP * error;
|
||||
|
||||
// limit how fast power changes (prevents oscillation)
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
}
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
robot.spin1.setPower(spindexer);
|
||||
robot.spin2.setPower(1-spindexer);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
return !spindexPosEqual(spindexer);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Shoot(double vel) {
|
||||
return new Action() {
|
||||
double transferStamp = 0.0;
|
||||
int ticker = 1;
|
||||
boolean transferIn = false;
|
||||
double currentPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
double initPos = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shooting");
|
||||
TELE.update();
|
||||
|
||||
if (ticker % 8 == 0) {
|
||||
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||
stamp = getRuntime();
|
||||
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||
initPos = currentPos;
|
||||
stamp1 = stamp;
|
||||
}
|
||||
|
||||
if (vel - velo > 500 && ticker > 16) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - vel > 500 && ticker > 16){
|
||||
powPID = 0.0;
|
||||
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = vel - velo;
|
||||
double correction = kP * error;
|
||||
|
||||
// limit how fast power changes (prevents oscillation)
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
}
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
|
||||
if (ticker == 1) {
|
||||
transferStamp = getRuntime();
|
||||
ticker++;
|
||||
}
|
||||
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("ticker", ticker);
|
||||
TELE.update();
|
||||
transferIn = true;
|
||||
return true;
|
||||
} else if (getRuntime() - transferStamp > waitTransfer+waitTransferOut && transferIn){
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shot once");
|
||||
TELE.update();
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double position = 0.0;
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
if ((getRuntime() % 0.3) > 0.15) {
|
||||
position = spindexer_intakePos1 + 0.02;
|
||||
} else {
|
||||
position = spindexer_intakePos1 - 0.02;
|
||||
}
|
||||
robot.spin1.setPower(position);
|
||||
robot.spin2.setPower(1 - position);
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Intaking");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(1);
|
||||
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action ColorDetect() {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
double position = 0.0;
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if ((getRuntime() % 0.3) > 0.15) {
|
||||
position = spindexer_intakePos1 + 0.02;
|
||||
} else {
|
||||
position = spindexer_intakePos1 - 0.02;
|
||||
}
|
||||
robot.spin1.setPower(position);
|
||||
robot.spin2.setPower(1 - position);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (s1D < 40) {
|
||||
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b1 = 2;
|
||||
} else {
|
||||
b1 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s2D < 40) {
|
||||
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b2 = 2;
|
||||
} else {
|
||||
b2 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s3D < 30) {
|
||||
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b3 = 2;
|
||||
} else {
|
||||
b3 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Detecting");
|
||||
TELE.addData("Distance 1", s1D);
|
||||
TELE.addData("Distance 2", s2D);
|
||||
TELE.addData("Distance 3", s3D);
|
||||
TELE.addData("B1", b1);
|
||||
TELE.addData("B2", b2);
|
||||
TELE.addData("B3", b3);
|
||||
TELE.update();
|
||||
|
||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new Flywheel();
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||
0, 0, 0
|
||||
));
|
||||
|
||||
aprilTag = new AprilTagWebcam();
|
||||
|
||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
aprilTag.init(robot, TELE);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
if (gamepad2.dpadUpWasPressed()) {
|
||||
hoodAuto-= 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.dpadDownWasPressed()) {
|
||||
hoodAuto += 0.01;
|
||||
}
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
robot.turr1.setPower(turret_detectBlue);
|
||||
robot.turr2.setPower(1 - turret_detectBlue);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.spin1.setPower(spindexer_intakePos1);
|
||||
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||
|
||||
aprilTag.update();
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()) {
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
initShooter(AUTO_CLOSE_VEL),
|
||||
Obelisk()
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup1.build(),
|
||||
intake(intake1Time)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot1.build(),
|
||||
ColorDetect(),
|
||||
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||
intakeReject()
|
||||
)
|
||||
);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
shootingSequence();
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup2.build(),
|
||||
intake(intake2Time)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot2.build(),
|
||||
ColorDetect(),
|
||||
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||
intakeReject()
|
||||
)
|
||||
);
|
||||
|
||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||
velo = flywheel.getVelo();
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("finished");
|
||||
TELE.update();
|
||||
|
||||
sleep(2000);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public void shootingSequence() {
|
||||
TELE.addData("Velocity", velo);
|
||||
if (gpp) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b2 == 2) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b3 == 2) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
}
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (pgp) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence4();
|
||||
TELE.addLine("sequence4");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
} else if (b2 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else if (b3 == 2) {
|
||||
sequence4();
|
||||
TELE.addLine("sequence4");
|
||||
}
|
||||
} else {
|
||||
sequence3();
|
||||
TELE.addLine("sequence3");
|
||||
}
|
||||
} else if (ppg) {
|
||||
if (b1 + b2 + b3 == 4) {
|
||||
if (b1 == 2 && b2 - b3 == 0) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||
sequence5();
|
||||
TELE.addLine("sequence5");
|
||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else if (b1 + b2 + b3 >= 5) {
|
||||
if (b1 == 2) {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
} else if (b2 == 2) {
|
||||
sequence5();
|
||||
TELE.addLine("sequence5");
|
||||
} else if (b3 == 2) {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
} else {
|
||||
sequence6();
|
||||
TELE.addLine("sequence6");
|
||||
}
|
||||
} else {
|
||||
sequence1();
|
||||
TELE.addLine("sequence1");
|
||||
}
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
public void sequence1() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence2() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence3() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence4() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence5() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence6() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,802 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_blueClose;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_redClose;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.AUTO_CLOSE_VEL;
|
||||
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinPow;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||
public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
public static double intake1Time = 2.7;
|
||||
public static double intake2Time = 3.0;
|
||||
public static double colorDetect = 3.0;
|
||||
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||
public static double slowSpeed = 30.0;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
Flywheel flywheel;
|
||||
Servos servo;
|
||||
double velo = 0.0;
|
||||
boolean gpp = false;
|
||||
boolean pgp = false;
|
||||
boolean ppg = false;
|
||||
public static double spinUnjamTime = 0.6;
|
||||
double powPID = 0.0;
|
||||
double bearing = 0.0;
|
||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||
|
||||
public Action initShooter(int vel) {
|
||||
return new Action() {
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
|
||||
return !flywheel.getSteady();
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Obelisk() {
|
||||
return new Action() {
|
||||
int id = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
id = fiducial.getFiducialId();
|
||||
TELE.addData("ID", id);
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (id == 21) {
|
||||
gpp = true;
|
||||
} else if (id == 22) {
|
||||
pgp = true;
|
||||
} else if (id == 23) {
|
||||
ppg = true;
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addData("21", gpp);
|
||||
TELE.addData("22", pgp);
|
||||
TELE.addData("23", ppg);
|
||||
TELE.update();
|
||||
|
||||
if (gpp || pgp || ppg) {
|
||||
if (redAlliance) {
|
||||
robot.limelight.pipelineSwitch(3);
|
||||
robot.turr1.setPosition(turret_redClose);
|
||||
robot.turr2.setPosition(1 - turret_redClose);
|
||||
return false;
|
||||
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
double turretPID = turret_blueClose;
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(1 - turretPID);
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action spindex(double spindexer, int vel) {
|
||||
return new Action() {
|
||||
double spinPID = 0.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (servo.spinEqual(spindexer)) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Shoot(int vel) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
double initPos = 0.0;
|
||||
double finalPos = 0.0;
|
||||
boolean zeroNeeded = false;
|
||||
boolean zeroPassed = false;
|
||||
double currentPos = 0.0;
|
||||
double prevPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shooting");
|
||||
TELE.update();
|
||||
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(-0.3);
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
robot.intake.setPower(0);
|
||||
|
||||
if (getRuntime() - stamp < 2.7) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
return true;
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action spindexUnjam(double jamTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
|
||||
|
||||
ticker++;
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
|
||||
if (ticker % 12 < 6) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
}
|
||||
|
||||
if (getRuntime() - stamp > jamTime+0.4) {
|
||||
|
||||
robot.intake.setPower(0.5);
|
||||
|
||||
return false;
|
||||
}
|
||||
else if (getRuntime() - stamp > jamTime) {
|
||||
|
||||
robot.intake.setPower(-(getRuntime()-stamp-jamTime)*2.5);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
else {
|
||||
robot.intake.setPower(1);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
double spinCurrentPos = 0.0;
|
||||
double spinInitPos = 0.0;
|
||||
boolean reverse = false;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (ticker % 60 < 12) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else if (ticker % 60 < 30) {
|
||||
robot.spin1.setPower(-0.5);
|
||||
robot.spin2.setPower(0.5);
|
||||
}
|
||||
else if (ticker % 60 < 42) {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
}
|
||||
else {
|
||||
robot.spin1.setPower(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
}
|
||||
robot.intake.setPower(1);
|
||||
TELE.addData("Reverse?", reverse);
|
||||
TELE.update();
|
||||
|
||||
if (getRuntime() - stamp > intakeTime) {
|
||||
if (reverse) {
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
} else {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
}
|
||||
return false;
|
||||
} else {
|
||||
if (ticker % 4 == 0) {
|
||||
spinCurrentPos = servo.getSpinPos();
|
||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
||||
spinInitPos = spinCurrentPos;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action ColorDetect(int vel) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (s1D < 43) {
|
||||
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b1 = 2;
|
||||
} else {
|
||||
b1 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s2D < 60) {
|
||||
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b2 = 2;
|
||||
} else {
|
||||
b2 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s3D < 33) {
|
||||
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b3 = 2;
|
||||
} else {
|
||||
b3 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Detecting");
|
||||
TELE.addData("Distance 1", s1D);
|
||||
TELE.addData("Distance 2", s2D);
|
||||
TELE.addData("Distance 3", s3D);
|
||||
TELE.addData("B1", b1);
|
||||
TELE.addData("B2", b2);
|
||||
TELE.addData("B3", b3);
|
||||
TELE.update();
|
||||
|
||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||
0, 0, 0
|
||||
));
|
||||
|
||||
servo = new Servos(hardwareMap);
|
||||
|
||||
robot.limelight.pipelineSwitch(1);
|
||||
robot.limelight.start();
|
||||
|
||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
//
|
||||
// TrajectoryActionBuilder lever = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
// .strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
||||
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
TrajectoryActionBuilder shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
if (gamepad2.dpadUpWasPressed()) {
|
||||
hoodAuto -= 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.dpadDownWasPressed()) {
|
||||
hoodAuto += 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.crossWasPressed()) {
|
||||
redAlliance = !redAlliance;
|
||||
|
||||
}
|
||||
|
||||
double turretPID;
|
||||
if (redAlliance) {
|
||||
turretPID = turret_redClose;
|
||||
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
// lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
// .strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup3 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx4a, ry4a), rh4a)
|
||||
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
shoot3 = drive.actionBuilder(new Pose2d(rx4b, ry4b, rh4b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
} else {
|
||||
turretPID = turret_blueClose;
|
||||
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turretPID);
|
||||
robot.turr2.setPosition(1 - turretPID);
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
TELE.addData("Red?", redAlliance);
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()) {
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
initShooter(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup1.build(),
|
||||
intake(intake1Time)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
shoot1.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup2.build(),
|
||||
intake(intake2Time)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot2.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
)
|
||||
);
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup3.build(),
|
||||
intake(intake2Time)
|
||||
)
|
||||
);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot3.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
shootingSequence();
|
||||
|
||||
robot.transfer.setPower(0);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("finished");
|
||||
TELE.update();
|
||||
|
||||
sleep(2000);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//TODO: adjust this according to Teleop numbers
|
||||
public void detectTag() {
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
bearing = result.getTx();
|
||||
}
|
||||
}
|
||||
double turretPos = (bearing / 1300);
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1 - turretPos);
|
||||
}
|
||||
|
||||
public void shootingSequence() {
|
||||
TELE.addLine("Shooting");
|
||||
TELE.update();
|
||||
Actions.runBlocking(Shoot(AUTO_CLOSE_VEL));
|
||||
}
|
||||
|
||||
public void sequence1() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence2() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence3() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence4() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence5() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public void sequence6() {
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL),
|
||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||
Shoot(AUTO_CLOSE_VEL)
|
||||
)
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
public class blank {
|
||||
}
|
||||
@@ -1,4 +1,5 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class Color {
|
||||
public static boolean redAlliance = true;
|
||||
}
|
||||
|
||||
@@ -12,40 +12,32 @@ public class Poses {
|
||||
|
||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||
|
||||
public static double x1 = 50, y1 = 0, h1 = 0;
|
||||
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
||||
|
||||
public static double x2 = 31, y2 = 32, h2 = Math.toRadians(140);
|
||||
public static double rx1 = 40, ry1 = -7, rh1 = 0;
|
||||
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
||||
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140);
|
||||
|
||||
public static double x2_b = 58, y2_b = 42, h2_b = Math.toRadians(140);
|
||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
|
||||
|
||||
public static double x3 = 34, y3 = 58, h3 = Math.toRadians(140);
|
||||
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
||||
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
|
||||
|
||||
public static double tx = 0, ty = 0, th = 0;
|
||||
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
|
||||
|
||||
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||
public static double bx1 = 40, by1 = 7, bh1 = 0;
|
||||
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140);
|
||||
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140);
|
||||
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140);
|
||||
|
||||
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
||||
|
||||
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||
|
||||
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
||||
|
||||
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
||||
|
||||
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||
|
||||
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
||||
|
||||
public static double rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
||||
|
||||
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
||||
|
||||
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
||||
|
||||
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||
|
||||
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||
|
||||
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||
|
||||
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
||||
|
||||
}
|
||||
|
||||
@@ -5,16 +5,16 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
public class ServoPositions {
|
||||
|
||||
public static double spindexer_intakePos1 = 0.665;
|
||||
public static double spindexer_intakePos1 = 0.18;
|
||||
|
||||
public static double spindexer_intakePos3 = 0.29;
|
||||
public static double spindexer_intakePos2 = 0.36;//0.5;
|
||||
|
||||
public static double spindexer_intakePos2 = 0.99;
|
||||
public static double spindexer_intakePos3 = 0.54;//0.66;
|
||||
|
||||
public static double spindexer_outtakeBall3 = 0.845;
|
||||
public static double spindexer_outtakeBall3 = 0.47;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.48;
|
||||
public static double spindexer_outtakeBall1 = 0.1;
|
||||
public static double spindexer_outtakeBall2 = 0.31;
|
||||
public static double spindexer_outtakeBall1 = 0.15;
|
||||
|
||||
public static double transferServo_out = 0.15;
|
||||
|
||||
@@ -24,18 +24,26 @@ public class ServoPositions {
|
||||
|
||||
public static double hoodDefault = 0.6;
|
||||
|
||||
public static double hoodAuto = 0.55;
|
||||
public static double hoodAuto = 0.27;
|
||||
|
||||
public static double hoodHigh = 0.21;
|
||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
||||
|
||||
public static double hoodLow = 1.0;
|
||||
public static double hoodHigh = 0.21; //TODO: change this;
|
||||
|
||||
public static double turret_red = 0.42;
|
||||
public static double turret_blue = 0.38;
|
||||
public static double hoodLow = 1.0; //TODO: change this;
|
||||
|
||||
public static double turret_detectRed = 0.2;
|
||||
public static double turret_redClose = 0.42;
|
||||
public static double turret_blueClose = 0.38;
|
||||
public static double turret_redFar = 0.5; //TODO: change this
|
||||
public static double turret_blueFar = 0.5; // TODO: change this
|
||||
|
||||
public static double turret_detectRedClose = 0.2;
|
||||
|
||||
public static double turret_detectBlueClose = 0.6;
|
||||
public static double turrDefault = 0.4;
|
||||
|
||||
public static double turrMin = 0.2;
|
||||
public static double turrMax = 0.8;
|
||||
|
||||
public static double turret_detectBlue = 0.6;
|
||||
public static double turrDefault = 0.40;
|
||||
|
||||
}
|
||||
|
||||
@@ -19,5 +19,8 @@ public class ShooterVars {
|
||||
public static double maxStep = 0.06; // prevents sudden jumps
|
||||
|
||||
// VELOCITY CONSTANTS
|
||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||
|
||||
public static Types.Motif currentMotif = Types.Motif.NONE;
|
||||
}
|
||||
@@ -0,0 +1,10 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class Types {
|
||||
public enum Motif {
|
||||
NONE,
|
||||
GPP, // Green, Purple, Purple
|
||||
PGP, // Purple, Green, Purple
|
||||
PPG // Purple, Purple, Green
|
||||
}
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class blank {
|
||||
}
|
||||
@@ -5,7 +5,9 @@ import androidx.annotation.NonNull;
|
||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.*;
|
||||
import com.acmerobotics.roadrunner.AccelConstraint;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.Actions;
|
||||
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
||||
import com.acmerobotics.roadrunner.DualNum;
|
||||
import com.acmerobotics.roadrunner.HolonomicController;
|
||||
@@ -14,12 +16,20 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
|
||||
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.Pose2dDual;
|
||||
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
||||
import com.acmerobotics.roadrunner.ProfileParams;
|
||||
import com.acmerobotics.roadrunner.Rotation2d;
|
||||
import com.acmerobotics.roadrunner.Time;
|
||||
import com.acmerobotics.roadrunner.TimeTrajectory;
|
||||
import com.acmerobotics.roadrunner.TimeTurn;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
|
||||
import com.acmerobotics.roadrunner.TurnConstraints;
|
||||
import com.acmerobotics.roadrunner.Twist2d;
|
||||
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.VelConstraint;
|
||||
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
||||
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||
@@ -46,13 +56,131 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
||||
|
||||
import java.lang.Math;
|
||||
import java.util.Arrays;
|
||||
import java.util.LinkedList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
public final class MecanumDrive {
|
||||
public static Params PARAMS = new Params();
|
||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||
public final VelConstraint defaultVelConstraint =
|
||||
new MinVelConstraint(Arrays.asList(
|
||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||
));
|
||||
public final AccelConstraint defaultAccelConstraint =
|
||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||
public final VoltageSensor voltageSensor;
|
||||
public final LazyImu lazyImu;
|
||||
public final Localizer localizer;
|
||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||
|
||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||
|
||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
//
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||
|
||||
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||
|
||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||
}
|
||||
|
||||
public void setDrivePowers(PoseVelocity2d powers) {
|
||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||
PoseVelocity2dDual.constant(powers, 1));
|
||||
|
||||
double maxPowerMag = 1;
|
||||
for (DualNum<Time> power : wheelVels.all()) {
|
||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||
}
|
||||
|
||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||
}
|
||||
|
||||
public PoseVelocity2d updatePoseEstimate() {
|
||||
PoseVelocity2d vel = localizer.update();
|
||||
poseHistory.add(localizer.getPose());
|
||||
|
||||
while (poseHistory.size() > 100) {
|
||||
poseHistory.removeFirst();
|
||||
}
|
||||
|
||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||
|
||||
return vel;
|
||||
}
|
||||
|
||||
private void drawPoseHistory(Canvas c) {
|
||||
double[] xPoints = new double[poseHistory.size()];
|
||||
double[] yPoints = new double[poseHistory.size()];
|
||||
|
||||
int i = 0;
|
||||
for (Pose2d t : poseHistory) {
|
||||
xPoints[i] = t.position.x;
|
||||
yPoints[i] = t.position.y;
|
||||
|
||||
i++;
|
||||
}
|
||||
|
||||
c.setStrokeWidth(1);
|
||||
c.setStroke("#3F51B5");
|
||||
c.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||
return new TrajectoryActionBuilder(
|
||||
TurnAction::new,
|
||||
FollowTrajectoryAction::new,
|
||||
new TrajectoryBuilderParams(
|
||||
1e-6,
|
||||
new ProfileParams(
|
||||
0.25, 0.1, 1e-2
|
||||
)
|
||||
),
|
||||
beginPose, 0.0,
|
||||
defaultTurnConstraints,
|
||||
defaultVelConstraint, defaultAccelConstraint
|
||||
);
|
||||
}
|
||||
|
||||
public static class Params {
|
||||
// IMU orientation
|
||||
// TODO: fill in these values based on
|
||||
@@ -91,35 +219,6 @@ public final class MecanumDrive {
|
||||
public double headingVelGain = 0.0; // shared with turn
|
||||
}
|
||||
|
||||
public static Params PARAMS = new Params();
|
||||
|
||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||
|
||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||
public final VelConstraint defaultVelConstraint =
|
||||
new MinVelConstraint(Arrays.asList(
|
||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||
));
|
||||
public final AccelConstraint defaultAccelConstraint =
|
||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||
|
||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||
|
||||
public final VoltageSensor voltageSensor;
|
||||
|
||||
public final LazyImu lazyImu;
|
||||
|
||||
public final Localizer localizer;
|
||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||
|
||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||
|
||||
public class DriveLocalizer implements Localizer {
|
||||
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
||||
public final IMU imu;
|
||||
@@ -144,13 +243,13 @@ public final class MecanumDrive {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setPose(Pose2d pose) {
|
||||
this.pose = pose;
|
||||
public Pose2d getPose() {
|
||||
return pose;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Pose2d getPose() {
|
||||
return pose;
|
||||
public void setPose(Pose2d pose) {
|
||||
this.pose = pose;
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -216,63 +315,10 @@ public final class MecanumDrive {
|
||||
}
|
||||
}
|
||||
|
||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||
|
||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||
|
||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
//
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||
|
||||
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||
|
||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||
}
|
||||
|
||||
public void setDrivePowers(PoseVelocity2d powers) {
|
||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||
PoseVelocity2dDual.constant(powers, 1));
|
||||
|
||||
double maxPowerMag = 1;
|
||||
for (DualNum<Time> power : wheelVels.all()) {
|
||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||
}
|
||||
|
||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||
}
|
||||
|
||||
public final class FollowTrajectoryAction implements Action {
|
||||
public final TimeTrajectory timeTrajectory;
|
||||
private double beginTs = -1;
|
||||
|
||||
private final double[] xPoints, yPoints;
|
||||
private double beginTs = -1;
|
||||
|
||||
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||
timeTrajectory = t;
|
||||
@@ -450,51 +496,4 @@ public final class MecanumDrive {
|
||||
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||
}
|
||||
}
|
||||
|
||||
public PoseVelocity2d updatePoseEstimate() {
|
||||
PoseVelocity2d vel = localizer.update();
|
||||
poseHistory.add(localizer.getPose());
|
||||
|
||||
while (poseHistory.size() > 100) {
|
||||
poseHistory.removeFirst();
|
||||
}
|
||||
|
||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||
|
||||
|
||||
return vel;
|
||||
}
|
||||
|
||||
private void drawPoseHistory(Canvas c) {
|
||||
double[] xPoints = new double[poseHistory.size()];
|
||||
double[] yPoints = new double[poseHistory.size()];
|
||||
|
||||
int i = 0;
|
||||
for (Pose2d t : poseHistory) {
|
||||
xPoints[i] = t.position.x;
|
||||
yPoints[i] = t.position.y;
|
||||
|
||||
i++;
|
||||
}
|
||||
|
||||
c.setStrokeWidth(1);
|
||||
c.setStroke("#3F51B5");
|
||||
c.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||
return new TrajectoryActionBuilder(
|
||||
TurnAction::new,
|
||||
FollowTrajectoryAction::new,
|
||||
new TrajectoryBuilderParams(
|
||||
1e-6,
|
||||
new ProfileParams(
|
||||
0.25, 0.1, 1e-2
|
||||
)
|
||||
),
|
||||
beginPose, 0.0,
|
||||
defaultTurnConstraints,
|
||||
defaultVelConstraint, defaultAccelConstraint
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -129,7 +129,7 @@ public class TeleopV2 extends LinearOpMode {
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
servo = new Servos(hardwareMap);
|
||||
flywheel = new Flywheel();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
|
||||
@@ -158,10 +158,6 @@ public class TeleopV2 extends LinearOpMode {
|
||||
robot.frontRight.setPower(frontRightPower);
|
||||
robot.backRight.setPower(backRightPower);
|
||||
|
||||
// PID SERVOS
|
||||
turretPID = servo.setTurrPos(turretPos);
|
||||
robot.turr1.setPower(turretPID);
|
||||
robot.turr2.setPower(-turretPID);
|
||||
|
||||
//TODO: make sure changing position works throughout opmode
|
||||
if (!servo.spinEqual(spindexPos)){
|
||||
@@ -286,10 +282,7 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
//SHOOTER:
|
||||
|
||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
||||
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
double powPID = flywheel.manageFlywheel((int) vel);
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
@@ -350,15 +343,28 @@ public class TeleopV2 extends LinearOpMode {
|
||||
overrideTurr = true;
|
||||
turretPos = servo.getTurrPos() - (bearing/1300);
|
||||
TELE.addData("Bear", bearing);
|
||||
if (camTicker < 8){
|
||||
error += bearing/1300; //adds error in first 8 frames of seeing the tag to see how much to adjust the default pos
|
||||
|
||||
double bearingCorrection = bearing / 1300;
|
||||
|
||||
|
||||
// deadband: ignore tiny noise
|
||||
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
||||
|
||||
// only accumulate if bearing direction is consistent
|
||||
if (Math.signum(bearingCorrection) == Math.signum(error) || error == 0) {
|
||||
error += bearingCorrection;
|
||||
}
|
||||
}
|
||||
|
||||
camTicker++;
|
||||
|
||||
}
|
||||
|
||||
|
||||
} else {
|
||||
camTicker = 0;
|
||||
overrideTurr = false;
|
||||
|
||||
}
|
||||
|
||||
if (manualTurret) {
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,55 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class ColorTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while(opModeIsActive()){
|
||||
double green1 = robot.color1.getNormalizedColors().green;
|
||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||
double red1 = robot.color1.getNormalizedColors().red;
|
||||
|
||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||
|
||||
// ----- COLOR 2 -----
|
||||
double green2 = robot.color2.getNormalizedColors().green;
|
||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||
double red2 = robot.color2.getNormalizedColors().red;
|
||||
|
||||
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
||||
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||
|
||||
// ----- COLOR 3 -----
|
||||
double green3 = robot.color3.getNormalizedColors().green;
|
||||
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||
double red3 = robot.color3.getNormalizedColors().red;
|
||||
|
||||
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
||||
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -5,6 +5,7 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
@@ -12,25 +13,45 @@ import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class IntakeTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Servos servo;
|
||||
|
||||
public boolean green1 = false;
|
||||
public boolean green2 = false;
|
||||
public boolean green3 = false;
|
||||
List<Double> s1G = new ArrayList<>();
|
||||
List<Double> s2G = new ArrayList<>();
|
||||
List<Double> s3G = new ArrayList<>();
|
||||
List<Double> s1T = new ArrayList<>();
|
||||
List<Double> s2T = new ArrayList<>();
|
||||
List<Double> s3T = new ArrayList<>();
|
||||
List<Boolean> s1 = new ArrayList<>();
|
||||
List<Boolean> s2 = new ArrayList<>();
|
||||
List<Boolean> s3 = new ArrayList<>();
|
||||
public static int mode = 0; // 0 for teleop, 1 for auto
|
||||
public static double manualPow = 1.0;
|
||||
public static double manualPow = 0.15;
|
||||
double stamp = 0;
|
||||
int ticker = 0;
|
||||
boolean b1 = false;
|
||||
boolean b2 = false;
|
||||
boolean b3 = false;
|
||||
boolean steadySpin = false;
|
||||
double powPID = 0.0;
|
||||
boolean intake = true;
|
||||
double spindexerPos = spindexer_intakePos1;
|
||||
boolean wasMoving = false;
|
||||
double currentPos = 0.0;
|
||||
double initPos = 0.0;
|
||||
boolean reverse = false;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||
for (LynxModule hub : allHubs) {
|
||||
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||
}
|
||||
robot = new Robot(hardwareMap);
|
||||
servo = new Servos(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
@@ -40,32 +61,44 @@ public class IntakeTest extends LinearOpMode {
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
//TODO: test tele intake with new spindexer
|
||||
if (mode == 0) {
|
||||
if (gamepad1.cross) {
|
||||
ticker = 0;
|
||||
if (gamepad1.right_bumper) {
|
||||
ticker++;
|
||||
if (ticker % 16 == 0){
|
||||
currentPos = servo.getSpinPos();
|
||||
if (Math.abs(currentPos - initPos) == 0.0){
|
||||
reverse = !reverse;
|
||||
}
|
||||
initPos = currentPos;
|
||||
}
|
||||
if (reverse){
|
||||
robot.spin1.setPower(manualPow);
|
||||
robot.spin2.setPower(-manualPow);
|
||||
} else {
|
||||
robot.spin1.setPower(-manualPow);
|
||||
robot.spin2.setPower(manualPow);
|
||||
}
|
||||
robot.intake.setPower(1);
|
||||
stamp = getRuntime();
|
||||
TELE.addData("Reverse?", reverse);
|
||||
TELE.update();
|
||||
} else {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
if (ticker == 0) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
if (getRuntime() - stamp < 0.5) {
|
||||
robot.intake.setPower(-1);
|
||||
|
||||
if (getRuntime() - stamp < 1) {
|
||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
}
|
||||
|
||||
ticker = 0;
|
||||
}
|
||||
//TODO: test this monstrosity
|
||||
} else if (mode == 1) {
|
||||
|
||||
if (gamepad1.cross){
|
||||
if (gamepad1.right_bumper && intake){
|
||||
robot.intake.setPower(1);
|
||||
} else if (gamepad1.circle){
|
||||
} else if (gamepad1.left_bumper){
|
||||
robot.intake.setPower(-1);
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
@@ -74,8 +107,8 @@ public class IntakeTest extends LinearOpMode {
|
||||
colorDetect();
|
||||
spindexer();
|
||||
|
||||
if (b1 && steadySpin && getRuntime() - stamp > 0.5){
|
||||
if (!b2){
|
||||
if (ballIn(1) && steadySpin && intake && getRuntime() - stamp > 0.5){
|
||||
if (!ballIn(2)){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
spindexerPos = spindexer_intakePos2;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
@@ -83,7 +116,7 @@ public class IntakeTest extends LinearOpMode {
|
||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||
spindexerPos = spindexer_intakePos1;
|
||||
}
|
||||
} else if (!b3){
|
||||
} else if (!ballIn(3)){
|
||||
if (servo.spinEqual(spindexer_intakePos1)){
|
||||
spindexerPos = spindexer_intakePos3;
|
||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||
@@ -94,74 +127,97 @@ public class IntakeTest extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
|
||||
powPID = servo.setSpinPos(spindexerPos);
|
||||
|
||||
} else if (mode == 2){ // switch to this mode before switching modes
|
||||
} else if (mode == 2){ // switch to this mode before switching modes or to reset balls
|
||||
powPID = 0;
|
||||
spindexerPos = spindexer_intakePos1;
|
||||
stamp = getRuntime();
|
||||
ticker = 0;
|
||||
spindexer();
|
||||
intake = true;
|
||||
}
|
||||
for (LynxModule hub : allHubs) {
|
||||
hub.clearBulkCache();
|
||||
}
|
||||
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
||||
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
||||
double rx = gamepad1.left_stick_x;
|
||||
|
||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||
double frontLeftPower = (y + x + rx) / denominator;
|
||||
double backLeftPower = (y - x + rx) / denominator;
|
||||
double frontRightPower = (y - x - rx) / denominator;
|
||||
double backRightPower = (y + x - rx) / denominator;
|
||||
|
||||
robot.frontLeft.setPower(frontLeftPower);
|
||||
robot.backLeft.setPower(backLeftPower);
|
||||
robot.frontRight.setPower(frontRightPower);
|
||||
robot.backRight.setPower(backRightPower);
|
||||
|
||||
TELE.addData("Manual Power", manualPow);
|
||||
TELE.addData("PID Power", powPID);
|
||||
TELE.addData("B1", b1);
|
||||
TELE.addData("B2", b2);
|
||||
TELE.addData("B3", b3);
|
||||
TELE.addData("B1", ballIn(1));
|
||||
TELE.addData("B2", ballIn(2));
|
||||
TELE.addData("B3", ballIn(3));
|
||||
TELE.addData("Spindex Pos", servo.getSpinPos());
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
|
||||
public void colorDetect() {
|
||||
// ----- COLOR 1 -----
|
||||
double green1 = robot.color1.getNormalizedColors().green;
|
||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||
double red1 = robot.color1.getNormalizedColors().red;
|
||||
|
||||
b1 = robot.color1.getDistance(DistanceUnit.MM) < 40;
|
||||
|
||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||
|
||||
// ----- COLOR 2 -----
|
||||
double green2 = robot.color2.getNormalizedColors().green;
|
||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||
double red2 = robot.color2.getNormalizedColors().red;
|
||||
|
||||
b2 = robot.color2.getDistance(DistanceUnit.MM) < 40;
|
||||
|
||||
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
||||
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||
|
||||
// ----- COLOR 3 -----
|
||||
double green3 = robot.color3.getNormalizedColors().green;
|
||||
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||
double red3 = robot.color3.getNormalizedColors().red;
|
||||
|
||||
b3 = robot.color3.getDistance(DistanceUnit.MM) < 30;
|
||||
|
||||
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
||||
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
TELE.addData("Color 1 Distance", s1D);
|
||||
TELE.addData("Color 2 Distance", s2D);
|
||||
TELE.addData("Color 3 Distance", s3D);
|
||||
TELE.update();
|
||||
|
||||
if (s1D < 43) {
|
||||
s1T.add(getRuntime());
|
||||
}
|
||||
|
||||
if (s2D < 60) {
|
||||
s2T.add(getRuntime());
|
||||
}
|
||||
|
||||
if (s3D < 33) {
|
||||
s3T.add(getRuntime());
|
||||
}
|
||||
}
|
||||
|
||||
public void spindexer() {
|
||||
if (!servo.spinEqual(spindexerPos)){
|
||||
boolean atTarget = servo.spinEqual(spindexerPos);
|
||||
|
||||
if (!atTarget) {
|
||||
powPID = servo.setSpinPos(spindexerPos);
|
||||
robot.spin1.setPower(powPID);
|
||||
robot.spin2.setPower(-powPID);
|
||||
|
||||
steadySpin = false;
|
||||
ticker = 0;
|
||||
wasMoving = true; // remember we were moving
|
||||
stamp = getRuntime();
|
||||
} else {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
steadySpin = true;
|
||||
if (ticker == 0){
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
wasMoving = false;
|
||||
}
|
||||
}
|
||||
|
||||
boolean ballIn(int slot) {
|
||||
List<Double> times;
|
||||
|
||||
if (slot == 1) {times = s1T;}
|
||||
else if (slot == 2) {times = s2T;}
|
||||
else if (slot == 3) {times = s3T;}
|
||||
else return false;
|
||||
|
||||
if (!times.isEmpty()){
|
||||
return times.get(times.size() - 1) > getRuntime() - 2;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -1,26 +1,34 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
//TODO: fix to get the apriltag that it is reading
|
||||
public class LimelightTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
public static int pipeline = 0; //0 is for test; 1, 2, and 3 are for obelisk; 4 is for blue track; 5 is for red track
|
||||
Turret turret;
|
||||
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 mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||
int obeliskPipe = 1;
|
||||
public static boolean turretMode = false;
|
||||
public static double turretPos = 0.501;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
robot = new Robot(hardwareMap);
|
||||
turret = new Turret(robot, TELE, robot.limelight);
|
||||
robot.limelight.pipelineSwitch(pipeline);
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
robot.limelight.start();
|
||||
while (opModeIsActive()){
|
||||
if (mode == 0){
|
||||
robot.limelight.pipelineSwitch(pipeline);
|
||||
@@ -33,41 +41,29 @@ public class LimelightTest extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
} else if (mode == 1){
|
||||
robot.limelight.pipelineSwitch(obeliskPipe);
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null && result.isValid()){
|
||||
TELE.addData("ID", obeliskPipe+20);
|
||||
int obeliskID = turret.detectObelisk();
|
||||
TELE.addData("Limelight ID", obeliskID);
|
||||
TELE.update();
|
||||
} else {
|
||||
if (obeliskPipe >= 3){
|
||||
obeliskPipe = 1;
|
||||
} else {
|
||||
obeliskPipe++;
|
||||
}
|
||||
}
|
||||
} else if (mode == 2){
|
||||
robot.limelight.pipelineSwitch(4);
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
TELE.addData("tx", result.getTx());
|
||||
TELE.addData("ty", result.getTy());
|
||||
} else if (mode == 2 || mode == 3){ // Use redAlliance variable to switch between red and blue
|
||||
double tx = turret.getBearing();
|
||||
double ty = turret.getTy();
|
||||
double x = turret.getLimelightX();
|
||||
double y = turret.getLimelightY();
|
||||
TELE.addData("tx", tx);
|
||||
TELE.addData("ty", ty);
|
||||
TELE.addData("x", x);
|
||||
TELE.addData("y", y);
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
} else if (mode == 3){
|
||||
robot.limelight.pipelineSwitch(5);
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
TELE.addData("tx", result.getTx());
|
||||
TELE.addData("ty", result.getTy());
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(0);
|
||||
}
|
||||
|
||||
if (turretMode){
|
||||
if (turretPos != 0.501){
|
||||
turret.manualSetTurret(turretPos);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6,8 +6,6 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@@ -33,7 +31,7 @@ public class PIDServoTest extends LinearOpMode {
|
||||
|
||||
PIDFController controller = new PIDFController(p, i, d, f);
|
||||
|
||||
controller.setTolerance(0);
|
||||
controller.setTolerance(0.001);
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
@@ -44,15 +42,7 @@ public class PIDServoTest extends LinearOpMode {
|
||||
|
||||
while (opModeIsActive()) {
|
||||
controller.setPIDF(p, i, d, f);
|
||||
|
||||
if (mode == 0) {
|
||||
pos = scalar * ((robot.turr1Pos.getVoltage() - restPos) / 3.3);
|
||||
|
||||
double pid = controller.calculate(pos, target);
|
||||
|
||||
robot.turr1.setPower(pid);
|
||||
robot.turr2.setPower(-pid);
|
||||
} else if (mode == 1) {
|
||||
if (mode == 1) {
|
||||
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
||||
|
||||
double pid = controller.calculate(pos, target);
|
||||
@@ -62,7 +52,6 @@ public class PIDServoTest extends LinearOpMode {
|
||||
}
|
||||
|
||||
telemetry.addData("pos", pos);
|
||||
telemetry.addData("Turret Voltage", robot.turr1Pos.getVoltage());
|
||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
||||
telemetry.addData("target", target);
|
||||
telemetry.addData("Mode", mode);
|
||||
@@ -71,4 +60,5 @@ public class PIDServoTest extends LinearOpMode {
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
@@ -1,6 +1,8 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@@ -11,30 +13,48 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class ShooterTest extends LinearOpMode {
|
||||
|
||||
public static int mode = 0;
|
||||
public static int mode = 1;
|
||||
public static double parameter = 0.0;
|
||||
// --- CONSTANTS YOU TUNE ---
|
||||
|
||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||
public static double Velocity = 0.0;
|
||||
public static double P = 255.0;
|
||||
public static double I = 0.0;
|
||||
public static double D = 0.0;
|
||||
public static double F = 7.5;
|
||||
public static double transferPower = 1.0;
|
||||
public static double hoodPos = 0.501;
|
||||
public static double turretPos = 0.501;
|
||||
public static boolean shoot = false;
|
||||
|
||||
public static boolean intake = false;
|
||||
Robot robot;
|
||||
Flywheel flywheel;
|
||||
|
||||
double shootStamp = 0.0;
|
||||
boolean shootAll = false;
|
||||
|
||||
public double spinPow = 0.09;
|
||||
|
||||
public static boolean enableHoodAutoOpen = false;
|
||||
public double hoodAdjust = 0.0;
|
||||
public static double hoodAdjustFactor = 1.0;
|
||||
Spindexer spindexer ;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
DcMotorEx leftShooter = robot.shooter1;
|
||||
DcMotorEx rightShooter = robot.shooter2;
|
||||
flywheel = new Flywheel();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -50,28 +70,68 @@ public class ShooterTest extends LinearOpMode {
|
||||
rightShooter.setPower(parameter);
|
||||
leftShooter.setPower(parameter);
|
||||
} else if (mode == 1) {
|
||||
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition());
|
||||
rightShooter.setPower(powPID);
|
||||
leftShooter.setPower(powPID);
|
||||
TELE.addData("PIDPower", powPID);
|
||||
flywheel.setPIDF(P, I, D, F);
|
||||
flywheel.manageFlywheel((int) Velocity);
|
||||
}
|
||||
|
||||
if (hoodPos != 0.501) {
|
||||
if (enableHoodAutoOpen) {
|
||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
||||
} else {
|
||||
robot.hood.setPosition(hoodPos);
|
||||
}
|
||||
|
||||
if (turretPos != 0.501) {
|
||||
robot.turr1.setPower(turretPos);
|
||||
robot.turr2.setPower(turretPos);
|
||||
}
|
||||
|
||||
robot.transfer.setPower(transferPower);
|
||||
if (intake) {
|
||||
robot.intake.setPower(1);
|
||||
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
}
|
||||
|
||||
|
||||
if (shoot) {
|
||||
shootStamp = getRuntime();
|
||||
shootAll = true;
|
||||
shoot = false;
|
||||
robot.transfer.setPower(transferPower);
|
||||
}
|
||||
if (shootAll) {
|
||||
|
||||
//intake = false;
|
||||
//reject = false;
|
||||
|
||||
// TODO: Change starting position based on desired order to shoot green ball
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
if (getRuntime() - shootStamp < 3.5) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
shootAll = false;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
robot.transfer.setPower(0);
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
}
|
||||
} else {
|
||||
spindexer.processIntake();
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Velocity 1", flywheel.getVelo1());
|
||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||
TELE.addData("Power", robot.shooter1.getPower());
|
||||
TELE.addData("Steady?", flywheel.getSteady());
|
||||
TELE.addData("Position", robot.shooter1.getCurrentPosition());
|
||||
|
||||
@@ -0,0 +1,50 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Autonomous
|
||||
@Config
|
||||
public class TurretTest extends LinearOpMode {
|
||||
public static boolean zeroTurr = false;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot robot = new Robot(hardwareMap);
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||
waitForStart();
|
||||
|
||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
||||
|
||||
while(opModeIsActive()){
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
turret.trackGoal(drive.localizer.getPose());
|
||||
|
||||
TELE.addData("tpos", turret.getTurrPos());
|
||||
TELE.addData("Limelight tx", turret.getBearing());
|
||||
TELE.addData("Limelight ty", turret.getTy());
|
||||
TELE.addData("Limelight X", turret.getLimelightX());
|
||||
TELE.addData("Limelight Y", turret.getLimelightY());
|
||||
|
||||
if(zeroTurr){
|
||||
turret.zeroTurretEncoder();
|
||||
}
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,88 +1,76 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||
|
||||
public class Flywheel {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
double initPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
double ticker = 0.0;
|
||||
double currentPos = 0.0;
|
||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||
double velo = 0.0;
|
||||
double velo1 = 0.0;
|
||||
double velo2 = 0.0;
|
||||
double velo3 = 0.0;
|
||||
double velo4 = 0.0;
|
||||
double velo5 = 0.0;
|
||||
public double velo1 = 0.0;
|
||||
public double velo2 = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
double powPID = 0.0;
|
||||
boolean steady = false;
|
||||
public Flywheel () {
|
||||
//robot = new Robot(hardwareMap);
|
||||
public Flywheel (HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
shooterPIDF1 = new PIDFCoefficients
|
||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||
shooterPIDF2 = new PIDFCoefficients
|
||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||
}
|
||||
|
||||
public double getVelo () {
|
||||
return velo;
|
||||
}
|
||||
public double getVelo1 () {
|
||||
return velo1;
|
||||
}
|
||||
public double getVelo2 () {
|
||||
return velo2;
|
||||
}
|
||||
|
||||
public boolean getSteady() {
|
||||
return steady;
|
||||
}
|
||||
|
||||
private double getTimeSeconds ()
|
||||
{
|
||||
return (double) System.currentTimeMillis()/1000.0;
|
||||
// Set the robot PIDF for the next cycle.
|
||||
public void setPIDF(double p, double i, double d, double f) {
|
||||
shooterPIDF1.p = p;
|
||||
shooterPIDF1.i = i;
|
||||
shooterPIDF1.d = d;
|
||||
shooterPIDF1.f = f;
|
||||
shooterPIDF2.p = p;
|
||||
shooterPIDF2.i = i;
|
||||
shooterPIDF2.d = d;
|
||||
shooterPIDF2.f = f;
|
||||
}
|
||||
|
||||
// Convert from RPM to Ticks per Second
|
||||
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
||||
|
||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||
// Convert from Ticks per Second to RPM
|
||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||
|
||||
public double manageFlywheel(double commandedVelocity) {
|
||||
targetVelocity = commandedVelocity;
|
||||
|
||||
ticker++;
|
||||
if (ticker % 2 == 0) {
|
||||
velo5 = velo4;
|
||||
velo4 = velo3;
|
||||
velo3 = velo2;
|
||||
velo2 = velo1;
|
||||
// Add code here to set PIDF based on desired RPM
|
||||
|
||||
currentPos = shooter1CurPos / 2048;
|
||||
stamp = getTimeSeconds(); //getRuntime();
|
||||
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||
initPos = currentPos;
|
||||
stamp1 = stamp;
|
||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
|
||||
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
||||
}
|
||||
// Flywheel control code here
|
||||
if (targetVelocity - velo > 500) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - targetVelocity > 500){
|
||||
powPID = 0.0;
|
||||
} else {
|
||||
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = targetVelocity - velo;
|
||||
double correction = kP * error;
|
||||
|
||||
// limit how fast power changes (prevents oscillation)
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
}
|
||||
// Record Current Velocity
|
||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||
velo = Math.max(velo1,velo2);
|
||||
|
||||
// really should be a running average of the last 5
|
||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
||||
|
||||
return powPID;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,110 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
|
||||
@Config
|
||||
public class FlywheelV2 {
|
||||
public static double kP = 0.001; // small proportional gain (tune this)
|
||||
public static double maxStep = 0.06; // prevents sudden jumps
|
||||
double initPos1 = 0.0;
|
||||
double initPos2 = 0.0;
|
||||
double stamp = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
double ticker = 0.0;
|
||||
double currentPos1 = 0.0;
|
||||
double currentPos2 = 0.0;
|
||||
double velo = 0.0;
|
||||
double velo1 = 0.0;
|
||||
double velo1a = 0.0;
|
||||
double velo1b = 0.0;
|
||||
double velo2 = 0.0;
|
||||
double velo3 = 0.0;
|
||||
double velo4 = 0.0;
|
||||
double velo5 = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
double powPID = 0.0;
|
||||
boolean steady = false;
|
||||
|
||||
public FlywheelV2() {
|
||||
//robot = new Robot(hardwareMap);
|
||||
}
|
||||
|
||||
public double getVelo(double shooter1CurPos, double shooter2CurPos) {
|
||||
ticker++;
|
||||
if (ticker % 2 == 0) {
|
||||
velo5 = velo4;
|
||||
velo4 = velo3;
|
||||
velo3 = velo2;
|
||||
velo2 = velo1;
|
||||
|
||||
currentPos1 = shooter1CurPos / 28;
|
||||
currentPos2 = shooter2CurPos / 28;
|
||||
stamp = getTimeSeconds(); //getRuntime();
|
||||
velo1a = 60 * ((currentPos1 - initPos1) / (stamp - stamp1));
|
||||
velo1b = 60 * ((currentPos2 - initPos2) / (stamp - stamp1));
|
||||
initPos1 = currentPos1;
|
||||
initPos2 = currentPos2;
|
||||
stamp1 = stamp;
|
||||
|
||||
if (velo1a < 200){
|
||||
velo1 = velo1b;
|
||||
} else if (velo1b < 200){
|
||||
velo1 = velo1a;
|
||||
} else {
|
||||
velo1 = (velo1a + velo1b) / 2;
|
||||
}
|
||||
}
|
||||
return ((velo1 + velo2 + velo3 + velo4 + velo5) / 5);
|
||||
}
|
||||
|
||||
public double getVelo1() { return (velo1a + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||
|
||||
public double getVelo2() { return (velo1b + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||
|
||||
public boolean getSteady() {
|
||||
return steady;
|
||||
}
|
||||
|
||||
private double getTimeSeconds() {
|
||||
return (double) System.currentTimeMillis() / 1000.0;
|
||||
}
|
||||
|
||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos, double shooter2CurPos) {
|
||||
targetVelocity = commandedVelocity;
|
||||
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
||||
// Flywheel PID code here
|
||||
if (targetVelocity - velo > 4500) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - targetVelocity > 4500) {
|
||||
powPID = 0.0;
|
||||
} else {
|
||||
|
||||
double a = 2539.07863;
|
||||
double c = 1967.6498;
|
||||
double d = -0.289647;
|
||||
double h = -1.1569;
|
||||
|
||||
double feed = Math.log10((a / (targetVelocity + c)) + d) / h;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = targetVelocity - velo;
|
||||
double correction = kP * error;
|
||||
|
||||
// limit how fast power changes (prevents oscillation)
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
}
|
||||
|
||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||
|
||||
return powPID;
|
||||
}
|
||||
|
||||
public void update() {
|
||||
}
|
||||
}
|
||||
@@ -8,6 +8,8 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class PositionalServoProgrammer extends LinearOpMode {
|
||||
@@ -25,11 +27,17 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
public static double hoodPos = 0.501;
|
||||
public static int mode = 0; //0 for positional, 1 for power
|
||||
|
||||
Turret turret;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
servo = new Servos(hardwareMap);
|
||||
|
||||
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight );
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
while (opModeIsActive()){
|
||||
@@ -44,16 +52,9 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
robot.spin1.setPower(spindexPow);
|
||||
robot.spin2.setPower(-spindexPow);
|
||||
}
|
||||
if (turretPos != 0.501 && !servo.turretEqual(turretPos)){
|
||||
double pos = servo.setTurrPos(turretPos);
|
||||
robot.turr1.setPower(pos);
|
||||
robot.turr2.setPower(-pos);
|
||||
} else if (mode == 0){
|
||||
robot.turr1.setPower(turrHoldPow);
|
||||
robot.turr2.setPower(turrHoldPow);
|
||||
} else {
|
||||
robot.spin1.setPower(turretPow);
|
||||
robot.spin2.setPower(-turretPow);
|
||||
if (turretPos != 0.501){
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1-turretPos);
|
||||
}
|
||||
if (transferPos != 0.501){
|
||||
robot.transferServo.setPosition(transferPos);
|
||||
@@ -61,13 +62,25 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
if (hoodPos != 0.501){
|
||||
robot.hood.setPosition(hoodPos);
|
||||
}
|
||||
TELE.addData("spindexer", servo.getSpinPos());
|
||||
TELE.addData("turret", servo.getTurrPos());
|
||||
TELE.addData("spindexer voltage", robot.spin1Pos.getVoltage());
|
||||
TELE.addData("hood voltage", robot.hoodPos.getVoltage());
|
||||
// To check configuration of spindexer:
|
||||
// Set "mode" to 1 and spindexPow to 0.1
|
||||
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
||||
// Do the previous test again to confirm
|
||||
// Set "mode" to 0 but keep spindexPos at 0.501
|
||||
// Manually turn the spindexer until "spindexer pos" is set close to 0
|
||||
// Check each spindexer voltage:
|
||||
// If "spindexer voltage 1" is closer to 0 than "spindexer voltage 2," then you are done!
|
||||
// If "spindexer voltage 2" is closer to 0 than "spindexer voltage 1," swap the two spindexer analog inputs in the configuration, DO NOT TOUCH THE ACTUAL CODE
|
||||
//TODO: @KeshavAnandCode do the above please
|
||||
|
||||
TELE.addData("spindexer pos", servo.getSpinPos());
|
||||
TELE.addData("turret pos", robot.turr1.getPosition());
|
||||
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||
TELE.addData("hood pos", robot.hood.getPosition());
|
||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||
TELE.addData("turret voltage", robot.turr1Pos.getVoltage());
|
||||
TELE.addData("Spin Equal", servo.spinEqual(spindexPos));
|
||||
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||
TELE.addData("tpos ", turret.getTurrPos() );
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||
@@ -7,87 +8,55 @@ import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||
|
||||
@Config
|
||||
public class Robot {
|
||||
|
||||
//Initialize Public Components
|
||||
|
||||
public static boolean usingLimelight = true;
|
||||
public static boolean usingCamera = false;
|
||||
public DcMotorEx frontLeft;
|
||||
public DcMotorEx frontRight;
|
||||
|
||||
public DcMotorEx backLeft;
|
||||
|
||||
public DcMotorEx backRight;
|
||||
|
||||
public DcMotorEx intake;
|
||||
|
||||
public DcMotorEx transfer;
|
||||
|
||||
public PIDFCoefficients shooterPIDF;
|
||||
public double shooterPIDF_P = 255.0;
|
||||
public double shooterPIDF_I = 0.0;
|
||||
public double shooterPIDF_D = 0.0;
|
||||
public double shooterPIDF_F = 7.5;
|
||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||
public DcMotorEx shooter1;
|
||||
public DcMotorEx shooter2;
|
||||
public Servo hood;
|
||||
|
||||
public Servo transferServo;
|
||||
|
||||
public Servo rejecter;
|
||||
|
||||
public CRServo turr1;
|
||||
|
||||
public CRServo turr2;
|
||||
|
||||
public Servo turr1;
|
||||
public Servo turr2;
|
||||
public CRServo spin1;
|
||||
|
||||
public CRServo spin2;
|
||||
|
||||
public DigitalChannel pin0;
|
||||
|
||||
public DigitalChannel pin1;
|
||||
public DigitalChannel pin2;
|
||||
public DigitalChannel pin3;
|
||||
public DigitalChannel pin4;
|
||||
|
||||
public DigitalChannel pin5;
|
||||
|
||||
public AnalogInput analogInput;
|
||||
|
||||
public AnalogInput analogInput2;
|
||||
|
||||
public AnalogInput spin1Pos;
|
||||
|
||||
public AnalogInput spin2Pos;
|
||||
|
||||
public AnalogInput hoodPos;
|
||||
|
||||
public AnalogInput turr1Pos;
|
||||
|
||||
public AnalogInput turr2Pos;
|
||||
|
||||
public AnalogInput transferServoPos;
|
||||
|
||||
public AprilTagProcessor aprilTagProcessor;
|
||||
|
||||
public WebcamName webcam;
|
||||
|
||||
public DcMotorEx shooterEncoder;
|
||||
|
||||
public RevColorSensorV3 color1;
|
||||
|
||||
public RevColorSensorV3 color2;
|
||||
|
||||
public RevColorSensorV3 color3;
|
||||
|
||||
public Limelight3A limelight;
|
||||
|
||||
public Robot(HardwareMap hardwareMap) {
|
||||
|
||||
//Define components w/ hardware map
|
||||
|
||||
//TODO: fix the configuration of these - I trust you to figure it out yourself @KeshavAnandCode
|
||||
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
|
||||
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
||||
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
||||
@@ -101,30 +70,29 @@ public class Robot {
|
||||
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||
|
||||
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
||||
rejecter = hardwareMap.get(Servo.class, "rejecter");
|
||||
|
||||
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
||||
|
||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||
|
||||
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
|
||||
shooterEncoder = shooter1;
|
||||
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F);
|
||||
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter1.setVelocity(0);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter2.setVelocity(0);
|
||||
|
||||
hood = hardwareMap.get(Servo.class, "hood");
|
||||
|
||||
hoodPos = hardwareMap.get(AnalogInput.class, "hoodPos");
|
||||
turr1 = hardwareMap.get(Servo.class, "t1");
|
||||
|
||||
turr1 = hardwareMap.get(CRServo.class, "t1");
|
||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||
|
||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos");
|
||||
|
||||
turr2 = hardwareMap.get(CRServo.class, "t2");
|
||||
|
||||
turr2Pos = hardwareMap.get(AnalogInput.class, "t2Pos");
|
||||
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
|
||||
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||
|
||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||
@@ -133,21 +101,8 @@ public class Robot {
|
||||
|
||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||
|
||||
pin0 = hardwareMap.get(DigitalChannel.class, "pin0");
|
||||
|
||||
pin1 = hardwareMap.get(DigitalChannel.class, "pin1");
|
||||
|
||||
pin2 = hardwareMap.get(DigitalChannel.class, "pin2");
|
||||
|
||||
pin3 = hardwareMap.get(DigitalChannel.class, "pin3");
|
||||
|
||||
pin4 = hardwareMap.get(DigitalChannel.class, "pin4");
|
||||
|
||||
pin5 = hardwareMap.get(DigitalChannel.class, "pin5");
|
||||
|
||||
analogInput = hardwareMap.get(AnalogInput.class, "analog");
|
||||
|
||||
analogInput2 = hardwareMap.get(AnalogInput.class, "analog2");
|
||||
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||
|
||||
@@ -156,10 +111,7 @@ public class Robot {
|
||||
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
||||
|
||||
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||
|
||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
|
||||
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
||||
|
||||
@@ -167,6 +119,11 @@ public class Robot {
|
||||
|
||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||
|
||||
limelight = hardwareMap.get(Limelight3A.class,"Limelight");
|
||||
if (usingLimelight) {
|
||||
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||
} else if (usingCamera) {
|
||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,30 +4,26 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@Config
|
||||
public class Servos {
|
||||
Robot robot;
|
||||
|
||||
PIDFController spinPID;
|
||||
|
||||
PIDFController turretPID;
|
||||
|
||||
//PID constants
|
||||
// TODO: get PIDF constants
|
||||
public static double spinP = 2.85, spinI = 0.015, spinD = 0.09, spinF = 0.03;
|
||||
public static double turrP = 4.0, turrI = 0.0, turrD = 0.0, turrF = 0.0;
|
||||
|
||||
public static double spin_scalar = 1.011;
|
||||
public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||
public static double spin_scalar = 1.0086;
|
||||
public static double spin_restPos = 0.0;
|
||||
public static double turret_scalar = 1.009;
|
||||
public static double turret_restPos = 0.0;
|
||||
Robot robot;
|
||||
PIDFController spinPID;
|
||||
PIDFController turretPID;
|
||||
|
||||
public Servos(HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
||||
|
||||
turretPID.setTolerance(0.001);
|
||||
}
|
||||
|
||||
// In the code below, encoder = robot.servo.getVoltage()
|
||||
@@ -35,6 +31,7 @@ public class Servos {
|
||||
public double getSpinPos() {
|
||||
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
||||
}
|
||||
|
||||
//TODO: PID warp so 0 and 1 are usable positions
|
||||
public double setSpinPos(double pos) {
|
||||
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
||||
@@ -43,20 +40,19 @@ public class Servos {
|
||||
}
|
||||
|
||||
public boolean spinEqual(double pos) {
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.01;
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return turret_scalar * ((robot.turr1Pos.getVoltage() - turret_restPos) / 3.3);
|
||||
return 1.0;
|
||||
|
||||
}
|
||||
|
||||
public double setTurrPos(double pos) {
|
||||
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
||||
|
||||
return spinPID.calculate(this.getTurrPos(), pos);
|
||||
return 1.0;
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,492 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.constants.Types;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
|
||||
public class Spindexer {
|
||||
|
||||
Robot robot;
|
||||
Servos servos;
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
double lastKnownSpinPos = 0.0;
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||
|
||||
double spinCurrentPos = 0.0;
|
||||
|
||||
public int commandedIntakePosition = 0;
|
||||
|
||||
public double distanceRearCenter = 0.0;
|
||||
public double distanceFrontDriver = 0.0;
|
||||
public double distanceFrontPassenger = 0.0;
|
||||
|
||||
public Types.Motif desiredMotif = Types.Motif.NONE;
|
||||
// For Use
|
||||
enum RotatedBallPositionNames {
|
||||
REARCENTER,
|
||||
FRONTDRIVER,
|
||||
FRONTPASSENGER
|
||||
}
|
||||
// Array of commandedIntakePositions with contents
|
||||
// {RearCenter, FrontDriver, FrontPassenger}
|
||||
static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}};
|
||||
class spindexerBallRoatation {
|
||||
int rearCenter = 0; // aka commanded Position
|
||||
int frontDriver = 0;
|
||||
int frontPassenger = 0;
|
||||
}
|
||||
|
||||
enum IntakeState {
|
||||
UNKNOWN_START,
|
||||
UNKNOWN_MOVE,
|
||||
UNKNOWN_DETECT,
|
||||
INTAKE,
|
||||
FINDNEXT,
|
||||
MOVING,
|
||||
FULL,
|
||||
SHOOTNEXT,
|
||||
SHOOTMOVING,
|
||||
SHOOTWAIT,
|
||||
SHOOT_ALL_PREP,
|
||||
SHOOT_ALL_READY
|
||||
};
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
public int unknownColorDetect = 0;
|
||||
enum BallColor {
|
||||
UNKNOWN,
|
||||
GREEN,
|
||||
PURPLE
|
||||
};
|
||||
|
||||
class BallPosition {
|
||||
boolean isEmpty = true;
|
||||
int foundEmpty = 0;
|
||||
BallColor ballColor = BallColor.UNKNOWN;
|
||||
}
|
||||
|
||||
BallPosition[] ballPositions = new BallPosition[3];
|
||||
|
||||
public boolean init () {
|
||||
return true;
|
||||
}
|
||||
|
||||
public Spindexer(HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
servos = new Servos(hardwareMap);
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
//TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
|
||||
lastKnownSpinPos = servos.getSpinPos();
|
||||
|
||||
ballPositions[0] = new BallPosition();
|
||||
ballPositions[1] = new BallPosition();
|
||||
ballPositions[2] = new BallPosition();
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
double[] outakePositions =
|
||||
{spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3};
|
||||
|
||||
double[] intakePositions =
|
||||
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
||||
|
||||
public int counter = 0;
|
||||
|
||||
// private double getTimeSeconds ()
|
||||
// {
|
||||
// return (double) System.currentTimeMillis()/1000.0;
|
||||
// }
|
||||
|
||||
// public double getPos() {
|
||||
// robot.spin1Pos.getVoltage();
|
||||
// robot.spin1Pos.getMaxVoltage();
|
||||
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
||||
// }
|
||||
|
||||
// public void manageSpindexer() {
|
||||
//
|
||||
// }
|
||||
|
||||
public void resetBallPosition (int pos) {
|
||||
ballPositions[pos].isEmpty = true;
|
||||
ballPositions[pos].foundEmpty = 0;
|
||||
ballPositions[pos].ballColor = BallColor.UNKNOWN;
|
||||
}
|
||||
|
||||
public void resetSpindexer () {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
resetBallPosition(i);
|
||||
}
|
||||
currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
}
|
||||
|
||||
// Detects if a ball is found and what color.
|
||||
// Returns true is there was a new ball found in Position 1
|
||||
// FIXIT: Reduce number of times that we read the color sensors for loop times.
|
||||
public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
|
||||
|
||||
boolean newPos1Detection = false;
|
||||
int spindexerBallPos = 0;
|
||||
|
||||
// Read Distances
|
||||
distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||
distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||
distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
// Position 1
|
||||
if (distanceRearCenter < 43) {
|
||||
|
||||
// Mark Ball Found
|
||||
newPos1Detection = true;
|
||||
|
||||
if (detectRearColor) {
|
||||
// Detect which color
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
// FIXIT - Add filtering to improve accuracy.
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
}
|
||||
// Position 2
|
||||
// Find which ball position this is in the spindexer
|
||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||
if (distanceFrontDriver < 60) {
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
if (detectFrontColor) {
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
resetBallPosition(spindexerBallPos);
|
||||
}
|
||||
ballPositions[spindexerBallPos].foundEmpty++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Position 3
|
||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
|
||||
if (distanceFrontPassenger < 33) {
|
||||
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
if (detectFrontColor) {
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
resetBallPosition(spindexerBallPos);
|
||||
}
|
||||
ballPositions[spindexerBallPos].foundEmpty++;
|
||||
}
|
||||
}
|
||||
|
||||
// TELE.addData("Velocity", velo);
|
||||
// TELE.addLine("Detecting");
|
||||
// TELE.addData("Distance 1", s1D);
|
||||
// TELE.addData("Distance 2", s2D);
|
||||
// TELE.addData("Distance 3", s3D);
|
||||
// TELE.addData("B1", b1);
|
||||
// TELE.addData("B2", b2);
|
||||
// TELE.addData("B3", b3);
|
||||
// TELE.update();
|
||||
|
||||
return newPos1Detection;
|
||||
}
|
||||
|
||||
public void moveSpindexerToPos(double pos) {
|
||||
spinCurrentPos = servos.getSpinPos();
|
||||
|
||||
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
||||
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
}
|
||||
|
||||
public void stopSpindexer() {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
}
|
||||
|
||||
public boolean isFull () {
|
||||
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
||||
}
|
||||
public boolean processIntake() {
|
||||
|
||||
switch (currentIntakeState) {
|
||||
case UNKNOWN_START:
|
||||
// For now just set position ONE if UNKNOWN
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(intakePositions[0]);
|
||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
|
||||
break;
|
||||
case UNKNOWN_MOVE:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
||||
stopSpindexer();
|
||||
unknownColorDetect = 0;
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
case UNKNOWN_DETECT:
|
||||
if (unknownColorDetect >5) {
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
} else {
|
||||
//detectBalls(true, true);
|
||||
unknownColorDetect++;
|
||||
}
|
||||
break;
|
||||
case INTAKE:
|
||||
// Ready for intake and Detecting a New Ball
|
||||
if (detectBalls(true, false)) {
|
||||
ballPositions[commandedIntakePosition].isEmpty = false;
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
} else {
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
case FINDNEXT:
|
||||
// Find Next Open Position and start movement
|
||||
double currentSpindexerPos = servos.getSpinPos();
|
||||
double commandedtravelDistance = 2.0;
|
||||
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 1
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 2
|
||||
commandedIntakePosition = 1;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 3
|
||||
commandedIntakePosition = 2;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||
// Full
|
||||
commandedIntakePosition = bestFitMotif();
|
||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||
}
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case MOVING:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
//detectBalls(false, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
|
||||
case FULL:
|
||||
// Double Check Colors
|
||||
detectBalls(false, false); // Minimize hardware calls
|
||||
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
||||
// Error handling found an empty spot, get it ready for a ball
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case SHOOT_ALL_PREP:
|
||||
// We get here with function call to prepareToShootMotif
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_READY;
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
}
|
||||
break;
|
||||
|
||||
case SHOOT_ALL_READY:
|
||||
// Double Check Colors
|
||||
//detectBalls(false, false); // Minimize hardware calls
|
||||
if (ballPositions[0].isEmpty && ballPositions[1].isEmpty && ballPositions[2].isEmpty) {
|
||||
// All ball shot move to intake state
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case SHOOTNEXT:
|
||||
// Find Next Open Position and start movement
|
||||
if (!ballPositions[0].isEmpty) {
|
||||
// Position 1
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty?
|
||||
// Position 2
|
||||
commandedIntakePosition = 1;
|
||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty?
|
||||
// Position 3
|
||||
commandedIntakePosition = 2;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else {
|
||||
// Empty return to intake state
|
||||
currentIntakeState = IntakeState.FINDNEXT;
|
||||
}
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
break;
|
||||
|
||||
case SHOOTMOVING:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
}
|
||||
break;
|
||||
|
||||
case SHOOTWAIT:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
//detectBalls(true, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
// Statements to execute if no case matches
|
||||
}
|
||||
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
||||
//TELE.update();
|
||||
// Signal a successful intake
|
||||
return false;
|
||||
}
|
||||
|
||||
public void setDesiredMotif (Types.Motif newMotif) {
|
||||
desiredMotif = newMotif;
|
||||
}
|
||||
|
||||
// Returns the best fit for the motiff
|
||||
public int bestFitMotif () {
|
||||
switch (desiredMotif) {
|
||||
case GPP:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 2;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
//break;
|
||||
case PGP:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 1;
|
||||
} else {
|
||||
return 3;
|
||||
}
|
||||
//break;
|
||||
case PPG:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 1;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else {
|
||||
return 2;
|
||||
}
|
||||
//break;
|
||||
case NONE:
|
||||
return 0;
|
||||
//break;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void prepareToShootMotif () {
|
||||
commandedIntakePosition = bestFitMotif();
|
||||
}
|
||||
|
||||
void shootAllToIntake () {
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
|
||||
public void update()
|
||||
{
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,141 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import android.provider.Settings;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
public class Targeting {
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
double cancelOffsetX = 0.0; // was -40.0
|
||||
double cancelOffsetY = 0.0; // was 7.0
|
||||
double unitConversionFactor = 0.95;
|
||||
|
||||
int tileSize = 24; //inches
|
||||
|
||||
public double robotInchesX, robotInchesY = 0.0;
|
||||
|
||||
public int robotGridX, robotGridY = 0;
|
||||
|
||||
|
||||
public static class Settings {
|
||||
public double flywheelRPM = 0.0;
|
||||
public double hoodAngle = 0.0;
|
||||
|
||||
public Settings (double flywheelRPM, double hoodAngle) {
|
||||
this.flywheelRPM = flywheelRPM;
|
||||
this.hoodAngle = hoodAngle;
|
||||
}
|
||||
}
|
||||
|
||||
// Known settings discovered using shooter test.
|
||||
// Keep the fidelity at 1 floor tile for now but we could also half it if more
|
||||
// accuracy is needed.
|
||||
public static final Settings[][] KNOWNTARGETING;
|
||||
static {
|
||||
KNOWNTARGETING = new Settings[6][6];
|
||||
// ROW 0 - Closet to the goals
|
||||
KNOWNTARGETING[0][0] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[0][1] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[0][2] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[0][3] = new Settings (2800.0, 0.68);
|
||||
KNOWNTARGETING[0][4] = new Settings (3000.0, 0.58);
|
||||
KNOWNTARGETING[0][5] = new Settings (3000.0, 0.58);
|
||||
// ROW 1
|
||||
KNOWNTARGETING[1][0] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[1][1] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[1][2] = new Settings (2600.0, 0.78);
|
||||
KNOWNTARGETING[1][3] = new Settings (2800.0, 0.62);
|
||||
KNOWNTARGETING[1][4] = new Settings (3000.0, 0.55);
|
||||
KNOWNTARGETING[1][5] = new Settings (3200.0, 0.50);
|
||||
// ROW 2
|
||||
KNOWNTARGETING[2][0] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[2][1] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[2][2] = new Settings (2700.0, 0.60);
|
||||
KNOWNTARGETING[2][3] = new Settings (2900.0, 0.53);
|
||||
KNOWNTARGETING[2][4] = new Settings (3100.0, 0.50);
|
||||
KNOWNTARGETING[2][5] = new Settings (3100.0, 0.50);
|
||||
// ROW 3
|
||||
KNOWNTARGETING[3][0] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][1] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][2] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][3] = new Settings (3100.0, 0.47);
|
||||
KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47);
|
||||
KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47);
|
||||
// ROW 4
|
||||
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
||||
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
||||
KNOWNTARGETING[4][2] = new Settings (4542.0, 0.1);
|
||||
KNOWNTARGETING[4][3] = new Settings (4543.0, 0.1);
|
||||
KNOWNTARGETING[4][4] = new Settings (4544.0, 0.1);
|
||||
KNOWNTARGETING[4][5] = new Settings (4545.0, 0.1);
|
||||
// ROW 1
|
||||
KNOWNTARGETING[5][0] = new Settings (4550.0, 0.1);
|
||||
KNOWNTARGETING[5][1] = new Settings (4551.0, 0.1);
|
||||
KNOWNTARGETING[5][2] = new Settings (4552.0, 0.1);
|
||||
KNOWNTARGETING[5][3] = new Settings (4553.0, 0.1);
|
||||
KNOWNTARGETING[5][4] = new Settings (4554.0, 0.1);
|
||||
KNOWNTARGETING[5][5] = new Settings (4555.0, 0.1);
|
||||
}
|
||||
|
||||
public Targeting()
|
||||
{
|
||||
}
|
||||
|
||||
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
||||
Settings recommendedSettings = new Settings(0.0, 0.0);
|
||||
|
||||
double cos45 = Math.cos(Math.toRadians(-45));
|
||||
double sin45 = Math.sin(Math.toRadians(-45));
|
||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
||||
|
||||
// Convert robot coordinates to inches
|
||||
robotInchesX = rotatedX * unitConversionFactor;
|
||||
robotInchesY = rotatedY * unitConversionFactor;
|
||||
|
||||
// Find approximate location in the grid
|
||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||
|
||||
//clamp
|
||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||
|
||||
// basic search
|
||||
if(!interpolate) {
|
||||
if ((robotGridY < 6) && (robotGridX <6)) {
|
||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
|
||||
}
|
||||
return recommendedSettings;
|
||||
} else {
|
||||
|
||||
// bilinear interpolation
|
||||
int x0 = robotGridX;
|
||||
int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
||||
int y0 = gridY;
|
||||
int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
||||
|
||||
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
||||
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
||||
|
||||
double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM;
|
||||
double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM;
|
||||
double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM;
|
||||
double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM;
|
||||
|
||||
double angle00 = KNOWNTARGETING[y0][x0].hoodAngle;
|
||||
double angle10 = KNOWNTARGETING[y0][x1].hoodAngle;
|
||||
double angle01 = KNOWNTARGETING[y1][x0].hoodAngle;
|
||||
double angle11 = KNOWNTARGETING[y1][x1].hoodAngle;
|
||||
|
||||
recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11;
|
||||
recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11;
|
||||
|
||||
return recommendedSettings;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,227 @@
|
||||
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
public class Turret {
|
||||
public static double turretTolerance = 0.02;
|
||||
public static double turrPosScalar = 0.00011264432;
|
||||
public static double turret180Range = 0.4;
|
||||
public static double turrDefault = 0.4;
|
||||
// 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 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;
|
||||
MultipleTelemetry TELE;
|
||||
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 ty = 0.0;
|
||||
double limelightPosX = 0.0;
|
||||
double limelightPosY = 0.0;
|
||||
public static double clampTolerance = 0.03;
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||
this.TELE = tele;
|
||||
this.robot = rob;
|
||||
this.webcam = cam;
|
||||
webcam.start();
|
||||
if (redAlliance){
|
||||
webcam.pipelineSwitch(3);
|
||||
} else {
|
||||
webcam.pipelineSwitch(2);
|
||||
}
|
||||
}
|
||||
|
||||
public void zeroTurretEncoder() {
|
||||
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
||||
|
||||
}
|
||||
|
||||
public void manualSetTurret(double pos){
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1-pos);
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||
}
|
||||
|
||||
private void limelightRead(){ // only for tracking purposes, not general reads
|
||||
if (redAlliance){
|
||||
webcam.pipelineSwitch(3);
|
||||
} else {
|
||||
webcam.pipelineSwitch(2);
|
||||
}
|
||||
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
tx = result.getTx();
|
||||
ty = result.getTy();
|
||||
// MegaTag1 code for receiving position
|
||||
Pose3D botpose = result.getBotpose();
|
||||
if (botpose != null){
|
||||
limelightPosX = botpose.getPosition().x;
|
||||
limelightPosY = botpose.getPosition().y;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public double getBearing() {
|
||||
tx = 1000;
|
||||
limelightRead();
|
||||
return tx;
|
||||
}
|
||||
|
||||
public double getTy(){
|
||||
limelightRead();
|
||||
return ty;
|
||||
}
|
||||
|
||||
public double getLimelightX(){
|
||||
limelightRead();
|
||||
return limelightPosX;
|
||||
}
|
||||
|
||||
public double getLimelightY(){
|
||||
limelightRead();
|
||||
return limelightPosY;
|
||||
}
|
||||
|
||||
public int detectObelisk() {
|
||||
webcam.pipelineSwitch(1);
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
}
|
||||
}
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
public int getObeliskID() {
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
public void zeroOffset() {
|
||||
offset = 0.0;
|
||||
}
|
||||
|
||||
public void lockOffset(boolean lock) {
|
||||
lockOffset = lock;
|
||||
}
|
||||
|
||||
/*
|
||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||
*/
|
||||
public void trackGoal(Pose2d deltaPos) {
|
||||
|
||||
controller.setPIDF(kP, kI, kD, kF);
|
||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||
|
||||
// Angle from robot to goal in robot frame
|
||||
double desiredTurretAngleDeg = Math.toDegrees(
|
||||
Math.atan2(deltaPos.position.y, deltaPos.position.x)
|
||||
);
|
||||
|
||||
// Robot heading (field → robot)
|
||||
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
|
||||
|
||||
// Turret angle needed relative to robot
|
||||
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
||||
|
||||
turretAngleDeg = -turretAngleDeg;
|
||||
|
||||
// Normalize to [-180, 180]
|
||||
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
||||
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
||||
|
||||
/* ---------------- APRILTAG CORRECTION ---------------- */
|
||||
//
|
||||
double tagBearingDeg = getBearing(); // + = target is to the left
|
||||
|
||||
turretAngleDeg += offset;
|
||||
|
||||
/* ---------------- ANGLE → SERVO ---------------- */
|
||||
|
||||
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
||||
|
||||
// Clamp to servo range
|
||||
double currentEncoderPos = this.getTurrPos();
|
||||
|
||||
if (!turretEqual(turretPos)) {
|
||||
double diff = turretPos - currentEncoderPos;
|
||||
turretPos = turretPos + diff * mult;
|
||||
}
|
||||
|
||||
if (currentEncoderPos < (turrMin + clampTolerance) || currentEncoderPos > (turrMax - clampTolerance)) {
|
||||
// Clamp to servo range
|
||||
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);
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1.0 - turretPos);
|
||||
|
||||
/* ---------------- TELEMETRY ---------------- */
|
||||
|
||||
TELE.addData("Turret Angle", turretAngleDeg);
|
||||
TELE.addData("Bearing", tagBearingDeg);
|
||||
TELE.addData("Offset", offset);
|
||||
}
|
||||
|
||||
}
|
||||
@@ -24,6 +24,10 @@ allprojects {
|
||||
}
|
||||
}
|
||||
|
||||
repositories {
|
||||
repositories {
|
||||
mavenCentral()
|
||||
google()
|
||||
maven { url 'https://maven.pedropathing.com' }
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user