Compare commits
8 Commits
301b5ec765
...
organize/e
| Author | SHA1 | Date | |
|---|---|---|---|
| 5931b2e7fa | |||
| 73f804bd2f | |||
| 0a81eb60d3 | |||
| 58e7289c7b | |||
| 46ed4f544f | |||
| e39fa396cb | |||
| 5e8727ebaa | |||
| c460a4fb7a |
@@ -0,0 +1,606 @@
|
|||||||
|
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.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.LimelightManager;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoClose_V3 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
LimelightManager limelightManager;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
public static double holdTurrPow = 0.1;
|
||||||
|
|
||||||
|
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b1 = 0, b2 = 0, b3 = 0;
|
||||||
|
boolean gpp = false, pgp = false, ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
|
||||||
|
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() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
limelightManager.update();
|
||||||
|
int id = limelightManager.detectFiducial();
|
||||||
|
|
||||||
|
if (id == 21) gpp = true;
|
||||||
|
else if (id == 22) pgp = true;
|
||||||
|
else if (id == 23) ppg = true;
|
||||||
|
|
||||||
|
TELE.addData("Fiducial ID", id);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
LimelightManager.LimelightMode mode = redAlliance ?
|
||||||
|
LimelightManager.LimelightMode.RED_GOAL :
|
||||||
|
LimelightManager.LimelightMode.BLUE_GOAL;
|
||||||
|
limelightManager.switchMode(mode);
|
||||||
|
|
||||||
|
double turretTarget = redAlliance ? turret_redClose : turret_blueClose;
|
||||||
|
double turretPID = servo.setTurrPos(turretTarget);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turretTarget);
|
||||||
|
}
|
||||||
|
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.setPower(holdTurrPow);
|
||||||
|
robot.turr2.setPower(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));
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
||||||
|
limelightManager.init();
|
||||||
|
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()){
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
}
|
||||||
|
|
||||||
|
double turrPID;
|
||||||
|
|
||||||
|
if (redAlliance){
|
||||||
|
turrPID = servo.setTurrPos(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 = servo.setTurrPos(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.setPower(turrPID);
|
||||||
|
robot.turr2.setPower(-turrPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
limelightManager.update();
|
||||||
|
bearing = limelightManager.getBearing();
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
|
||||||
|
// Define sequences based on obelisk configuration
|
||||||
|
double[][] sequences = {
|
||||||
|
{1, 2, 3}, {1, 3, 2}, {2, 1, 3}, {2, 3, 1}, {3, 1, 2}, {3, 2, 1}
|
||||||
|
};
|
||||||
|
|
||||||
|
double[] sequence = null;
|
||||||
|
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[0]; // 1,2,3
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[2]; // 2,1,3
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[4]; // 3,1,2
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[0];
|
||||||
|
else if (b2 == 2) sequence = sequences[2];
|
||||||
|
else if (b3 == 2) sequence = sequences[4];
|
||||||
|
} else sequence = sequences[0];
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[2]; // 2,1,3
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[0]; // 1,2,3
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[3]; // 2,3,1
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[2];
|
||||||
|
else if (b2 == 2) sequence = sequences[0];
|
||||||
|
else if (b3 == 2) sequence = sequences[3];
|
||||||
|
} else sequence = sequences[2];
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[4]; // 3,1,2
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[5]; // 3,2,1
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[0]; // 1,2,3
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[4];
|
||||||
|
else if (b2 == 2) sequence = sequences[5];
|
||||||
|
else if (b3 == 2) sequence = sequences[0];
|
||||||
|
} else sequence = sequences[4];
|
||||||
|
} else sequence = sequences[0];
|
||||||
|
|
||||||
|
executeShootingSequence(sequence);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
private void executeShootingSequence(double[] sequence) {
|
||||||
|
double[] ballPositions = {
|
||||||
|
spindexer_outtakeBall1,
|
||||||
|
spindexer_outtakeBall2,
|
||||||
|
spindexer_outtakeBall3
|
||||||
|
};
|
||||||
|
|
||||||
|
for (double ball : sequence) {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(ballPositions[(int) ball - 1], AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,619 @@
|
|||||||
|
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.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.LimelightManager;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoFar_V1 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
LimelightManager limelightManager;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
public static double holdTurrPow = 0.1;
|
||||||
|
|
||||||
|
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b1 = 0, b2 = 0, b3 = 0;
|
||||||
|
boolean gpp = false, pgp = false, ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
|
||||||
|
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() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
limelightManager.update();
|
||||||
|
int id = limelightManager.detectFiducial();
|
||||||
|
|
||||||
|
if (id == 21) gpp = true;
|
||||||
|
else if (id == 22) pgp = true;
|
||||||
|
else if (id == 23) ppg = true;
|
||||||
|
|
||||||
|
TELE.addData("Fiducial ID", id);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
LimelightManager.LimelightMode mode = redAlliance ?
|
||||||
|
LimelightManager.LimelightMode.RED_GOAL :
|
||||||
|
LimelightManager.LimelightMode.BLUE_GOAL;
|
||||||
|
limelightManager.switchMode(mode);
|
||||||
|
|
||||||
|
double turretTarget = redAlliance ? turret_redFar : turret_blueFar;
|
||||||
|
double turretPID = servo.setTurrPos(turretTarget);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turretTarget);
|
||||||
|
}
|
||||||
|
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.setPower(holdTurrPow);
|
||||||
|
robot.turr2.setPower(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));
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
||||||
|
limelightManager.init();
|
||||||
|
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
||||||
|
|
||||||
|
//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 = servo.setTurrPos(turret_detectRedClose);
|
||||||
|
} else {
|
||||||
|
turrPID = servo.setTurrPos(turret_detectBlueClose);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPower(turrPID);
|
||||||
|
robot.turr2.setPower(-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() {
|
||||||
|
limelightManager.update();
|
||||||
|
bearing = limelightManager.getBearing();
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_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)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -178,8 +178,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (gpp || pgp || ppg){
|
if (gpp || pgp || ppg){
|
||||||
robot.turr1.setPower(turret_blue);
|
robot.turr1.setPower(turret_blueClose);
|
||||||
robot.turr2.setPower(1 - turret_blue);
|
robot.turr2.setPower(1 - turret_blueClose);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -541,8 +541,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
robot.turr1.setPower(turret_detectBlue);
|
robot.turr1.setPower(turret_detectBlueClose);
|
||||||
robot.turr2.setPower(1 - turret_detectBlue);
|
robot.turr2.setPower(1 - turret_detectBlueClose);
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
|||||||
@@ -169,10 +169,10 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (gpp || pgp || ppg){
|
if (gpp || pgp || ppg){
|
||||||
double turretPID = servo.setTurrPos(turret_red);
|
double turretPID = servo.setTurrPos(turret_redClose);
|
||||||
robot.turr1.setPower(turretPID);
|
robot.turr1.setPower(turretPID);
|
||||||
robot.turr2.setPower(-turretPID);
|
robot.turr2.setPower(-turretPID);
|
||||||
return !servo.turretEqual(turret_red);
|
return !servo.turretEqual(turret_redClose);
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,40 +12,22 @@ public class Poses {
|
|||||||
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
public static double x1 = 50, y1 = 0, h1 = 0;
|
|
||||||
|
|
||||||
public static double x2 = 31, y2 = 32, h2 = Math.toRadians(140);
|
|
||||||
|
|
||||||
public static double x2_b = 58, y2_b = 42, h2_b = Math.toRadians(140);
|
|
||||||
|
|
||||||
public static double x3 = 34, y3 = 58, h3 = Math.toRadians(140);
|
|
||||||
|
|
||||||
public static double tx = 0, ty = 0, th = 0;
|
|
||||||
|
|
||||||
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
||||||
|
|
||||||
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
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 rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx3a = 58, ry3a = 42, rh3a = 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 rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
||||||
|
|
||||||
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
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 bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||||
|
|
||||||
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||||
|
|
||||||
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -26,16 +26,20 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double hoodAuto = 0.55;
|
public static double hoodAuto = 0.55;
|
||||||
|
|
||||||
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 hoodLow = 1.0; //TODO: change this;
|
||||||
public static double turret_blue = 0.38;
|
|
||||||
|
|
||||||
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_detectBlue = 0.6;
|
public static double turret_detectRedClose = 0.2;
|
||||||
|
|
||||||
|
public static double turret_detectBlueClose = 0.6;
|
||||||
public static double turrDefault = 0.40;
|
public static double turrDefault = 0.40;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -20,4 +20,5 @@ public class ShooterVars {
|
|||||||
|
|
||||||
// VELOCITY CONSTANTS
|
// VELOCITY CONSTANTS
|
||||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||||
|
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||||
}
|
}
|
||||||
@@ -3,14 +3,12 @@ package org.firstinspires.ftc.teamcode.teleop;
|
|||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransfer;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransferOut;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.lynx.LynxModule;
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
@@ -18,6 +16,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
@@ -32,6 +31,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
Servos servo;
|
Servos servo;
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
|
LimelightManager limelightManager;
|
||||||
|
|
||||||
public static double manualVel = 3000;
|
public static double manualVel = 3000;
|
||||||
public static double hoodDefaultPos = 0.5;
|
public static double hoodDefaultPos = 0.5;
|
||||||
@@ -102,15 +102,15 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
servo = new Servos(hardwareMap);
|
servo = new Servos(hardwareMap);
|
||||||
flywheel = new Flywheel();
|
flywheel = new Flywheel();
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
||||||
|
limelightManager.init();
|
||||||
|
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
robot.limelight.pipelineSwitch(3);
|
limelightManager.switchMode(LimelightManager.LimelightMode.RED_GOAL);
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
limelightManager.switchMode(LimelightManager.LimelightMode.BLUE_GOAL);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.limelight.start();
|
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
@@ -305,30 +305,26 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1) { //not moving
|
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1) { //not moving
|
||||||
double bearing;
|
limelightManager.update();
|
||||||
|
double bearing = limelightManager.getBearing();
|
||||||
|
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
if (limelightManager.getLatestResult() != null && limelightManager.getLatestResult().isValid()) {
|
||||||
if (result != null) {
|
overrideTurr = true;
|
||||||
if (result.isValid()) {
|
turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
bearing = result.getTx();
|
|
||||||
overrideTurr = true;
|
|
||||||
turretPos = servo.getTurrPos() - (bearing / 1300);
|
|
||||||
|
|
||||||
double bearingCorrection = bearing / 1300;
|
double bearingCorrection = bearing / 1300;
|
||||||
|
|
||||||
// deadband: ignore tiny noise
|
// deadband: ignore tiny noise
|
||||||
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
||||||
|
// only accumulate if bearing direction is consistent
|
||||||
// only accumulate if bearing direction is consistent
|
if (Math.signum(bearingCorrection) == Math.signum(error) ||
|
||||||
if (Math.signum(bearingCorrection) == Math.signum(error) ||
|
error == 0) {
|
||||||
error == 0) {
|
error += bearingCorrection;
|
||||||
error += bearingCorrection;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
camTicker++;
|
|
||||||
TELE.addData("tx", bearing);
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
}
|
}
|
||||||
|
camTicker++;
|
||||||
|
TELE.addData("tx", bearing);
|
||||||
|
TELE.addData("ty", limelightManager.getLatestResult().getTy());
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -205,7 +205,6 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
boolean ballIn(int slot) {
|
boolean ballIn(int slot) {
|
||||||
List<Double> times;
|
List<Double> times;
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,104 @@
|
|||||||
|
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 > 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));
|
||||||
|
}
|
||||||
|
|
||||||
|
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||||
|
|
||||||
|
return powPID;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,103 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class LimelightManager {
|
||||||
|
private Limelight3A limelight;
|
||||||
|
private LLResult lastResult;
|
||||||
|
private int lastFiducialId = -1;
|
||||||
|
private double lastBearing = 0.0;
|
||||||
|
|
||||||
|
public static final int PIPELINE_DEFAULT = 1;
|
||||||
|
public static final int PIPELINE_BLUE_DETECTION = 2;
|
||||||
|
public static final int PIPELINE_RED_DETECTION = 3;
|
||||||
|
|
||||||
|
public enum LimelightMode {
|
||||||
|
OBELISK_DETECTION(PIPELINE_DEFAULT),
|
||||||
|
BLUE_GOAL(PIPELINE_BLUE_DETECTION),
|
||||||
|
RED_GOAL(PIPELINE_RED_DETECTION);
|
||||||
|
|
||||||
|
public final int pipeline;
|
||||||
|
|
||||||
|
LimelightMode(int pipeline) {
|
||||||
|
this.pipeline = pipeline;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public LimelightManager(HardwareMap hardwareMap, boolean enabled) {
|
||||||
|
if (enabled) {
|
||||||
|
this.limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void init() {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.start();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void switchMode(LimelightMode mode) {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.pipelineSwitch(mode.pipeline);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setPipeline(int pipeline) {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.pipelineSwitch(pipeline);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
if (limelight != null) {
|
||||||
|
lastResult = limelight.getLatestResult();
|
||||||
|
if (lastResult != null && lastResult.isValid()) {
|
||||||
|
lastBearing = lastResult.getTx();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getBearing() {
|
||||||
|
return lastBearing;
|
||||||
|
}
|
||||||
|
|
||||||
|
public int detectFiducial() {
|
||||||
|
if (lastResult != null && lastResult.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = lastResult.getFiducialResults();
|
||||||
|
if (!fiducials.isEmpty()) {
|
||||||
|
lastFiducialId = fiducials.get(0).getFiducialId();
|
||||||
|
return lastFiducialId;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
public int getLastFiducialId() {
|
||||||
|
return lastFiducialId;
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isFiducialDetected(int id) {
|
||||||
|
return lastFiducialId == id;
|
||||||
|
}
|
||||||
|
|
||||||
|
public LLResult getLatestResult() {
|
||||||
|
return lastResult;
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isConnected() {
|
||||||
|
return limelight != null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public Limelight3A getLimelight() {
|
||||||
|
return limelight;
|
||||||
|
}
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user