Compare commits
10 Commits
263bd46320
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
| d586e3b4df | |||
| 2f5d4638ec | |||
| 1642e161c5 | |||
| 46a565c2c8 | |||
| 0838fc35f9 | |||
| 17643535ae | |||
| 5d93e3fc59 | |||
| fb8a4fae95 | |||
| b68f7eb6e7 | |||
| d1f658cb5b |
@@ -0,0 +1,804 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.*;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.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
|
||||
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 = 6.5;
|
||||
|
||||
public static double intake2Time = 6.5;
|
||||
|
||||
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.setPosition(turret_blue);
|
||||
robot.turr2.setPosition(1 - turret_blue);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
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.setPosition(spindexer);
|
||||
robot.spin2.setPosition(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.setPosition(position);
|
||||
robot.spin2.setPosition(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) {
|
||||
robot.intake.setPower(0);
|
||||
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.setPosition(position);
|
||||
robot.spin2.setPosition(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.setPosition(turret_detectBlue);
|
||||
robot.turr2.setPosition(1 - turret_detectBlue);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.spin1.setPosition(spindexer_intakePos1);
|
||||
robot.spin2.setPosition(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)
|
||||
)
|
||||
);
|
||||
|
||||
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)
|
||||
)
|
||||
);
|
||||
|
||||
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,804 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.*;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@Config
|
||||
@Autonomous
|
||||
public class Red_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 = 6.5;
|
||||
|
||||
public static double intake2Time = 6.5;
|
||||
|
||||
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.setPosition(turret_red);
|
||||
robot.turr2.setPosition(1 - turret_red);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
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.setPosition(spindexer);
|
||||
robot.spin2.setPosition(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.setPosition(position);
|
||||
robot.spin2.setPosition(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) {
|
||||
robot.intake.setPower(0);
|
||||
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.setPosition(position);
|
||||
robot.spin2.setPosition(1 - position);
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (s1D < 40) {
|
||||
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b1 = 2;
|
||||
} else {
|
||||
b1 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s2D < 40) {
|
||||
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b2 = 2;
|
||||
} else {
|
||||
b2 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (s3D < 30) {
|
||||
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
b3 = 2;
|
||||
} else {
|
||||
b3 = 1;
|
||||
}
|
||||
}
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("Detecting");
|
||||
TELE.addData("Distance 1", s1D);
|
||||
TELE.addData("Distance 2", s2D);
|
||||
TELE.addData("Distance 3", s3D);
|
||||
TELE.addData("B1", b1);
|
||||
TELE.addData("B2", b2);
|
||||
TELE.addData("B3", b3);
|
||||
TELE.update();
|
||||
|
||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new Flywheel();
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||
0, 0, 0
|
||||
));
|
||||
|
||||
aprilTag = new AprilTagWebcam();
|
||||
|
||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
aprilTag.init(robot, TELE);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
if (gamepad2.dpadUpWasPressed()) {
|
||||
hoodAuto-= 0.01;
|
||||
}
|
||||
|
||||
if (gamepad2.dpadDownWasPressed()) {
|
||||
hoodAuto += 0.01;
|
||||
}
|
||||
|
||||
robot.hood.setPosition(hoodAuto);
|
||||
|
||||
robot.turr1.setPosition(turret_detectRed);
|
||||
robot.turr2.setPosition(1 - turret_detectRed);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.spin1.setPosition(spindexer_intakePos1);
|
||||
robot.spin2.setPosition(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)
|
||||
)
|
||||
);
|
||||
|
||||
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)
|
||||
)
|
||||
);
|
||||
|
||||
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)
|
||||
)
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -21,8 +21,31 @@ public class Poses {
|
||||
public static double x3 = 34, y3 = 58, h3 = Math.toRadians(140);
|
||||
|
||||
public static double tx = 0, ty = 0, th = 0;
|
||||
public static Pose2d teleStart = new Pose2d(tx, ty, th);
|
||||
|
||||
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||
|
||||
|
||||
|
||||
public static double rx1 = 46, ry1 = -4, 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 = 46, by1 = 4, bh1 = 0;
|
||||
|
||||
public static double bx2a = 45, by2a = -5, bh2a = Math.toRadians(-140);
|
||||
|
||||
public static double bx2b = 31, by2b = -32, bh2b = Math.toRadians(-140);
|
||||
|
||||
public static double bx3a = 58, by3a = -42, bh3a = Math.toRadians(-140);
|
||||
|
||||
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||
|
||||
public static Pose2d teleStart = new Pose2d(rx1, 10, 0);
|
||||
|
||||
}
|
||||
|
||||
@@ -1,6 +1,5 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
|
||||
@Config
|
||||
@@ -21,15 +20,22 @@ public class ServoPositions {
|
||||
|
||||
public static double transferServo_in = 0.38;
|
||||
|
||||
public static double hoodDefault = 0.35;
|
||||
public static double turret_range = 0.9;
|
||||
|
||||
public static double hoodDefault = 0.6;
|
||||
|
||||
public static double hoodAuto = 0.59;
|
||||
|
||||
public static double hoodHigh = 0.21;
|
||||
|
||||
public static double hoodLow = 1.0;
|
||||
|
||||
public static double turret_red = 0.43;
|
||||
public static double turret_blue = 0.4;
|
||||
public static double turret_range = 0.9;
|
||||
public static double turret_red = 0.4;
|
||||
public static double turret_blue = 0.38;
|
||||
|
||||
public static double turret_detectRed = 0.2;
|
||||
|
||||
public static double turret_detectBlue = 0.6;
|
||||
public static double turrDefault = 0.40;
|
||||
|
||||
}
|
||||
|
||||
@@ -12,8 +12,12 @@ public class ShooterVars {
|
||||
|
||||
public static int initTolerance = 1000;
|
||||
|
||||
public static int maxVel = 4000;
|
||||
public static int maxVel = 4500;
|
||||
public static double waitTransferOut = 0.3;
|
||||
public static double waitTransfer = 0.4;
|
||||
public static double waitTransferOut = 0.6;
|
||||
public static double kP = 0.001; // small proportional gain (tune this)
|
||||
public static double maxStep = 0.06; // prevents sudden jumps
|
||||
|
||||
// VELOCITY CONSTANTS
|
||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||
}
|
||||
@@ -7,6 +7,7 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
|
||||
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.turrDefault;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransfer;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransferOut;
|
||||
import static org.firstinspires.ftc.teamcode.tests.ShooterTest.kP;
|
||||
@@ -17,13 +18,16 @@ import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.sca
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
@@ -37,14 +41,28 @@ public class TeleopV2 extends LinearOpMode {
|
||||
public static double hoodDefaultPos = 0.5;
|
||||
public static double desiredTurretAngle = 180;
|
||||
public static double velMultiplier = 20;
|
||||
public static double shootStamp2 = 0.0;
|
||||
|
||||
|
||||
public double vel = 3000;
|
||||
public boolean autoVel = true;
|
||||
public double manualOffset = 0.0;
|
||||
public boolean autoHood = true;
|
||||
public boolean green1 = false;
|
||||
public boolean green2 = false;
|
||||
public boolean green3 = false;
|
||||
public double shootStamp = 0.0;
|
||||
public boolean circle = false;
|
||||
public boolean square = false;
|
||||
public boolean triangle = false;
|
||||
double autoHoodOffset = 0.0;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
boolean intake = false;
|
||||
boolean reject = false;
|
||||
double xOffset = 0.0;
|
||||
double yOffset = 0.0;
|
||||
double headingOffset = 0.0;
|
||||
int ticker = 0;
|
||||
List<Double> s1G = new ArrayList<>();
|
||||
List<Double> s2G = new ArrayList<>();
|
||||
@@ -55,6 +73,8 @@ public class TeleopV2 extends LinearOpMode {
|
||||
List<Boolean> s1 = new ArrayList<>();
|
||||
List<Boolean> s2 = new ArrayList<>();
|
||||
List<Boolean> s3 = new ArrayList<>();
|
||||
boolean oddBallColor = false;
|
||||
AprilTagWebcam aprilTagWebcam = new AprilTagWebcam();
|
||||
MecanumDrive drive;
|
||||
double hoodOffset = 0.0;
|
||||
boolean shoot1 = false;
|
||||
@@ -62,12 +82,16 @@ public class TeleopV2 extends LinearOpMode {
|
||||
boolean shootA = true;
|
||||
boolean shootB = true;
|
||||
boolean shootC = true;
|
||||
boolean manualTurret = false;
|
||||
|
||||
boolean outtake1 = false;
|
||||
boolean outtake2 = false;
|
||||
boolean outtake3 = false;
|
||||
boolean overrideTurr = false;
|
||||
|
||||
public boolean green1 = false;
|
||||
public boolean green2 = false;
|
||||
public boolean green3 = false;
|
||||
|
||||
List<Integer> shootOrder = new ArrayList<>();
|
||||
boolean emergency = false;
|
||||
private double lastEncoderRevolutions = 0.0;
|
||||
private double lastTimeStamp = 0.0;
|
||||
private double velo1, velo;
|
||||
@@ -79,17 +103,17 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
public static double velPrediction(double distance) {
|
||||
|
||||
if (distance < 40) {
|
||||
return 2650;
|
||||
} else if (distance > 120) {
|
||||
if (distance < 30) {
|
||||
return 2750;
|
||||
} else if (distance > 100) {
|
||||
if (distance > 160) {
|
||||
return 4200;
|
||||
}
|
||||
return 3600;
|
||||
return 3700;
|
||||
} else {
|
||||
// linear interpolation between 40->2650 and 120->3600
|
||||
double slope = (3600.0 - 2650.0) / (120.0 - 40.0);
|
||||
return (int) Math.round(2650 + slope * (distance - 40));
|
||||
double slope = (3700.0 - 2750.0) / (100.0 - 30);
|
||||
return (int) Math.round(2750 + slope * (distance - 30));
|
||||
}
|
||||
|
||||
}
|
||||
@@ -110,6 +134,13 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
|
||||
Pose2d shootPos = teleStart;
|
||||
|
||||
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
||||
|
||||
robot.turr1.setPosition(0.4);
|
||||
robot.turr2.setPosition(1 - 0.4);
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
while (opModeIsActive()) {
|
||||
@@ -134,11 +165,22 @@ public class TeleopV2 extends LinearOpMode {
|
||||
//INTAKE:
|
||||
|
||||
if (gamepad1.rightBumperWasPressed()) {
|
||||
intake = true;
|
||||
intake = !intake;
|
||||
reject = false;
|
||||
shootAll = false;
|
||||
emergency = false;
|
||||
overrideTurr = false;
|
||||
|
||||
|
||||
}
|
||||
|
||||
if (gamepad1.leftBumperWasPressed()) {
|
||||
intake = false;
|
||||
reject = true;
|
||||
shootAll = false;
|
||||
overrideTurr = false;
|
||||
|
||||
|
||||
}
|
||||
|
||||
if (intake) {
|
||||
@@ -231,16 +273,16 @@ public class TeleopV2 extends LinearOpMode {
|
||||
s3T.add(getRuntime());
|
||||
}
|
||||
|
||||
|
||||
if (!s1.isEmpty()) {
|
||||
green1 = checkGreen(s1, s1T);
|
||||
}
|
||||
if (!s2.isEmpty()) {
|
||||
green2 = checkGreen(s2, s2T);
|
||||
|
||||
}
|
||||
if (!s3.isEmpty()) {
|
||||
green3 = checkGreen(s3, s3T);
|
||||
}
|
||||
}
|
||||
|
||||
//SHOOTER:
|
||||
|
||||
@@ -294,8 +336,9 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
double offset;
|
||||
|
||||
double robotX = drive.localizer.getPose().position.x;
|
||||
double robotY = drive.localizer.getPose().position.y;
|
||||
double robotX = drive.localizer.getPose().position.x - xOffset;
|
||||
double robotY = drive.localizer.getPose().position.y - xOffset;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -10;
|
||||
double goalY = 0;
|
||||
@@ -309,13 +352,13 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
desiredTurretAngle += manualOffset;
|
||||
|
||||
offset = desiredTurretAngle - 180 - Math.toDegrees(drive.localizer.getPose().heading.toDouble());
|
||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||
|
||||
if (offset > 135) {
|
||||
offset -= 360;
|
||||
}
|
||||
|
||||
double pos = 0.4;
|
||||
double pos = turrDefault;
|
||||
|
||||
TELE.addData("offset", offset);
|
||||
|
||||
@@ -323,17 +366,24 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
if (pos < 0.02) {
|
||||
pos = 0.02;
|
||||
} else if (pos > 0.91) {
|
||||
pos = 0.91;
|
||||
} else if (pos > 0.97) {
|
||||
pos = 0.97;
|
||||
}
|
||||
|
||||
if (manualTurret) {
|
||||
pos = turrDefault + (manualOffset / 100);
|
||||
}
|
||||
|
||||
if (!overrideTurr) {
|
||||
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1 - pos);
|
||||
}
|
||||
|
||||
if (gamepad2.dpad_right) {
|
||||
manualOffset -= 4;
|
||||
manualOffset -= 2;
|
||||
} else if (gamepad2.dpad_left) {
|
||||
manualOffset += 4;
|
||||
manualOffset += 2;
|
||||
}
|
||||
|
||||
//VELOCITY AUTOMATIC
|
||||
@@ -346,67 +396,172 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
if (gamepad2.right_stick_button) {
|
||||
autoVel = true;
|
||||
} else if (Math.abs(gamepad2.right_stick_y) > 0.5) {
|
||||
} else if (gamepad2.right_stick_y < -0.5) {
|
||||
autoVel = false;
|
||||
manualVel -= gamepad2.right_stick_y * velMultiplier;
|
||||
manualVel = 4100;
|
||||
} else if (gamepad2.right_stick_y > 0.5) {
|
||||
autoVel = false;
|
||||
manualVel = 2700;
|
||||
} else if (gamepad2.right_stick_x > 0.5) {
|
||||
autoVel = false;
|
||||
manualVel = 3600;
|
||||
} else if (gamepad2.right_stick_x < -0.5) {
|
||||
autoVel = false;
|
||||
manualVel = 3100;
|
||||
}
|
||||
|
||||
//HOOD:
|
||||
|
||||
if (autoHood) {
|
||||
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal));
|
||||
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
||||
} else {
|
||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||
}
|
||||
|
||||
if (gamepad2.dpadUpWasPressed()) {
|
||||
hoodOffset -= 0.03;
|
||||
autoHoodOffset -= 0.02;
|
||||
|
||||
} else if (gamepad2.dpadDownWasPressed()) {
|
||||
hoodOffset += 0.03;
|
||||
autoHoodOffset += 0.02;
|
||||
|
||||
}
|
||||
|
||||
if (gamepad2.leftStickButtonWasPressed()) {
|
||||
autoHood = !autoHood;
|
||||
if (gamepad2.left_stick_x > 0.5) {
|
||||
manualTurret = false;
|
||||
} else if (gamepad2.left_stick_x < -0.5) {
|
||||
manualTurret = true;
|
||||
manualOffset = 0;
|
||||
autoHoodOffset = 0;
|
||||
if (gamepad2.left_bumper) {
|
||||
xOffset = robotX;
|
||||
yOffset = robotY;
|
||||
headingOffset = robotHeading;
|
||||
}
|
||||
}
|
||||
|
||||
//SHOOT ALL:
|
||||
if (gamepad2.left_stick_y < -0.5) {
|
||||
autoHood = true;
|
||||
} else if (gamepad2.left_stick_y > 0.5) {
|
||||
autoHood = false;
|
||||
hoodOffset = 0;
|
||||
if (gamepad2.left_bumper) {
|
||||
xOffset = robotX;
|
||||
yOffset = robotY;
|
||||
headingOffset = robotHeading;
|
||||
}
|
||||
}
|
||||
|
||||
//SHOOT ALL:]
|
||||
|
||||
if (shootAll) {
|
||||
if (emergency) {
|
||||
intake = false;
|
||||
reject = false;
|
||||
|
||||
TELE.addData("works","w");
|
||||
if (getRuntime() % 3 > 1.5) {
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(1);
|
||||
} else {
|
||||
|
||||
robot.spin1.setPosition(1);
|
||||
robot.spin2.setPosition(0);
|
||||
}
|
||||
|
||||
if (getRuntime() % 1 < 0.5) {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
}
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
} else if (shootAll) {
|
||||
|
||||
TELE.addData("100% works", shootOrder);
|
||||
|
||||
intake = false;
|
||||
reject = false;
|
||||
|
||||
if (!shootOrder.isEmpty()) {
|
||||
if (!shootOrder.isEmpty() && (getRuntime() - shootStamp < 12)) {
|
||||
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
||||
boolean shootingDone = false;
|
||||
|
||||
AprilTagDetection d20 = aprilTagWebcam.getTagById(20);
|
||||
AprilTagDetection d24 = aprilTagWebcam.getTagById(24);
|
||||
|
||||
if (d20 != null) {
|
||||
overrideTurr = true;
|
||||
double bearing = d20.ftcPose.bearing;
|
||||
double finalPos =robot.turr1.getPosition() - (bearing/1300);
|
||||
robot.turr1.setPosition(finalPos);
|
||||
robot.turr2.setPosition(1-finalPos);
|
||||
|
||||
TELE.addData("Bear", bearing);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
if (d24 != null) {
|
||||
overrideTurr = true;
|
||||
|
||||
double bearing = d24.ftcPose.bearing;
|
||||
double finalPos = turretPos() + (bearing/720);
|
||||
robot.turr1.setPosition(finalPos);
|
||||
robot.turr2.setPosition(1-finalPos);
|
||||
|
||||
}
|
||||
|
||||
if (!outtake1) {
|
||||
outtake1 = (spindexPosEqual(spindexer_outtakeBall1));
|
||||
}
|
||||
if (!outtake2) {
|
||||
outtake2 = (spindexPosEqual(spindexer_outtakeBall2));
|
||||
}
|
||||
if (!outtake3) {
|
||||
outtake3 = (spindexPosEqual(spindexer_outtakeBall3));
|
||||
}
|
||||
|
||||
switch (currentSlot) {
|
||||
case 1:
|
||||
shootA = shootTeleop(spindexer_outtakeBall3);
|
||||
shootA = shootTeleop(spindexer_outtakeBall1, outtake1, shootStamp2);
|
||||
TELE.addData("shootA", shootA);
|
||||
shootingDone = !shootA; // shootA is false when done
|
||||
|
||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||
shootingDone = !shootA;
|
||||
} else {
|
||||
shootingDone = true;
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
shootB = shootTeleop(spindexer_outtakeBall2);
|
||||
shootB = shootTeleop(spindexer_outtakeBall2, outtake2, shootStamp2);
|
||||
TELE.addData("shootB", shootB);
|
||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||
shootingDone = !shootB;
|
||||
} else {
|
||||
shootingDone = true;
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
shootC = shootTeleop(spindexer_outtakeBall1);
|
||||
shootC = shootTeleop(spindexer_outtakeBall3, outtake3, shootStamp2);
|
||||
TELE.addData("shootC", shootC);
|
||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||
shootingDone = !shootC;
|
||||
} else {
|
||||
shootingDone = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// Remove from the list only if shooting is complete
|
||||
if (shootingDone) {
|
||||
shootOrder.remove(0);
|
||||
shootStamp2 = getRuntime();
|
||||
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -416,14 +571,52 @@ public class TeleopV2 extends LinearOpMode {
|
||||
shootA = true;
|
||||
shootB = true;
|
||||
shootC = true;
|
||||
reject = false;
|
||||
intake = true;
|
||||
shootAll = false;
|
||||
}
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
overrideTurr = false;
|
||||
|
||||
|
||||
TELE.update();
|
||||
|
||||
}
|
||||
|
||||
if (gamepad2.squareWasPressed() || gamepad2.triangleWasPressed() || gamepad2.circleWasPressed()) {
|
||||
}
|
||||
|
||||
if (gamepad2.squareWasPressed()) {
|
||||
square = true;
|
||||
shootStamp = getRuntime();
|
||||
shootStamp2 = getRuntime();
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
}
|
||||
|
||||
if (gamepad2.circleWasPressed()) {
|
||||
circle = true;
|
||||
shootStamp = getRuntime();
|
||||
shootStamp2 = getRuntime();
|
||||
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
|
||||
}
|
||||
|
||||
if (gamepad2.triangleWasPressed()) {
|
||||
triangle = true;
|
||||
shootStamp = getRuntime();
|
||||
shootStamp2 = getRuntime();
|
||||
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
|
||||
}
|
||||
|
||||
if (square || circle || triangle) {
|
||||
|
||||
// Count green balls
|
||||
int greenCount = 0;
|
||||
@@ -432,36 +625,105 @@ public class TeleopV2 extends LinearOpMode {
|
||||
if (green3) greenCount++;
|
||||
|
||||
// Determine the odd ball color
|
||||
boolean oddBallColor = greenCount < 2; // true = green, false = purple
|
||||
oddBallColor = greenCount < 2; // true = green, false = purple
|
||||
|
||||
shootOrder.clear();
|
||||
|
||||
// Determine shooting order based on button pressed
|
||||
// square = odd ball first, triangle = odd ball second, circle = odd ball third
|
||||
if (gamepad2.squareWasPressed()) {
|
||||
if (square) {
|
||||
// Odd ball first
|
||||
addOddThenRest(shootOrder, oddBallColor);
|
||||
} else if (gamepad2.triangleWasPressed()) {
|
||||
|
||||
} else if (triangle) {
|
||||
// Odd ball second
|
||||
addOddInMiddle(shootOrder, oddBallColor);
|
||||
} else if (gamepad2.circleWasPressed()) {
|
||||
} else if (circle) {
|
||||
// Odd ball last
|
||||
addOddLast(shootOrder, oddBallColor);
|
||||
}
|
||||
|
||||
shootAll = true;
|
||||
circle = false;
|
||||
square = false;
|
||||
triangle = false;
|
||||
|
||||
}
|
||||
|
||||
// Right bumper shoots all balls fastest, ignoring colors
|
||||
if (gamepad2.rightBumperWasPressed()) {
|
||||
shootOrder.clear();
|
||||
shootStamp = getRuntime();
|
||||
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
|
||||
// Fastest order (example: slot 3 → 2 → 1)
|
||||
|
||||
if (ballIn(3)){
|
||||
shootOrder.add(3);
|
||||
|
||||
}
|
||||
|
||||
if (ballIn(2)){
|
||||
shootOrder.add(2);
|
||||
|
||||
}
|
||||
|
||||
if (ballIn(1)){
|
||||
shootOrder.add(1);
|
||||
|
||||
}
|
||||
|
||||
if (!shootOrder.contains(3)) {
|
||||
|
||||
shootOrder.add(3);
|
||||
}
|
||||
|
||||
if (!shootOrder.contains(2)) {
|
||||
|
||||
shootOrder.add(2);
|
||||
}
|
||||
|
||||
if (!shootOrder.contains(1)) {
|
||||
|
||||
shootOrder.add(1);
|
||||
}
|
||||
|
||||
|
||||
shootAll = true;
|
||||
shootPos = drive.localizer.getPose();
|
||||
|
||||
}
|
||||
|
||||
// Right bumper shoots all balls fastest, ignoring colors
|
||||
if (gamepad2.leftBumperWasPressed()) {
|
||||
shootOrder.clear();
|
||||
shootStamp = getRuntime();
|
||||
|
||||
outtake1 = false;
|
||||
outtake2 = false;
|
||||
outtake3 = false;
|
||||
|
||||
// Fastest order (example: slot 3 → 2 → 1)
|
||||
|
||||
if (ballIn(3)) {
|
||||
shootOrder.add(3);
|
||||
}
|
||||
|
||||
if (ballIn(2)) {
|
||||
shootOrder.add(2);
|
||||
}
|
||||
if (ballIn(1)) {
|
||||
shootOrder.add(1);
|
||||
}
|
||||
shootAll = true;
|
||||
shootPos = drive.localizer.getPose();
|
||||
|
||||
}
|
||||
|
||||
if (gamepad2.crossWasPressed()) {
|
||||
emergency = !emergency;
|
||||
|
||||
}
|
||||
|
||||
@@ -473,17 +735,20 @@ public class TeleopV2 extends LinearOpMode {
|
||||
hub.clearBulkCache();
|
||||
}
|
||||
|
||||
TELE.addData("Spin1Green", green1);
|
||||
TELE.addData("Spin2Green", green2);
|
||||
TELE.addData("Spin3Green", green3);
|
||||
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
||||
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
||||
TELE.addData("Spin3Green", green3 + ": " + ballIn(3));
|
||||
|
||||
TELE.addData("pose", drive.localizer.getPose());
|
||||
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
||||
TELE.addData("distanceToGoal", distanceToGoal);
|
||||
TELE.addData("hood", robot.hood.getPosition());
|
||||
TELE.addData("targetVel", manualVel);
|
||||
TELE.addData("targetVel", vel);
|
||||
|
||||
TELE.addData("shootOrder", shootOrder);
|
||||
TELE.addData("oddColor", oddBallColor);
|
||||
|
||||
aprilTagWebcam.update();
|
||||
|
||||
TELE.update();
|
||||
|
||||
@@ -518,13 +783,13 @@ public class TeleopV2 extends LinearOpMode {
|
||||
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||
}
|
||||
|
||||
public boolean shootTeleop(double spindexer) {
|
||||
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
||||
// Set spin positions
|
||||
robot.spin1.setPosition(spindexer);
|
||||
robot.spin2.setPosition(1 - spindexer);
|
||||
|
||||
// Check if spindexer has reached the target position
|
||||
if (spindexPosEqual(spindexer)) {
|
||||
if (spinOk || getRuntime() - stamp > 1.5) {
|
||||
if (tickerA == 1) {
|
||||
transferStamp = getRuntime();
|
||||
tickerA++;
|
||||
@@ -560,38 +825,125 @@ public class TeleopV2 extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
|
||||
public double hoodAnglePrediction(double distance) {
|
||||
public double hoodAnglePrediction(double x) {
|
||||
if (x < 34) {
|
||||
double L = 1.04471;
|
||||
double U = 0.711929;
|
||||
double Q = 120.02263;
|
||||
double B = 0.780982;
|
||||
double M = 20.61191;
|
||||
double v = 10.40506;
|
||||
|
||||
return 0.4;
|
||||
double inner = 1 + Q * Math.exp(-B * (x - M));
|
||||
return L + (U - L) / Math.pow(inner, 1.0 / v);
|
||||
|
||||
} else {
|
||||
// x >= 34
|
||||
return 1.94372 * Math.exp(-0.0528731 * x) + 0.39;
|
||||
}
|
||||
}
|
||||
|
||||
void addOddThenRest(List<Integer> order, boolean oddColor) {
|
||||
// Odd ball first
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||
TELE.addData("1", shootOrder);
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||
TELE.addData("works", shootOrder);
|
||||
TELE.addData("oddBall", oddColor);
|
||||
shootAll = true;
|
||||
|
||||
}
|
||||
|
||||
void addOddInMiddle(List<Integer> order, boolean oddColor) {
|
||||
// Odd ball second
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor && !order.contains(i)) order.add(i);
|
||||
|
||||
boolean[] used = new boolean[4]; // index 1..3
|
||||
|
||||
// 1) Add a NON-odd ball first
|
||||
for (int i = 1; i <= 3; i++) {
|
||||
if (getBallColor(i) != oddColor) {
|
||||
order.add(i);
|
||||
used[i] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// 2) Add the odd ball second
|
||||
for (int i = 1; i <= 3; i++) {
|
||||
if (!used[i] && getBallColor(i) == oddColor) {
|
||||
order.add(i);
|
||||
used[i] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// 3) Add the remaining non-odd ball third
|
||||
for (int i = 1; i <= 3; i++) {
|
||||
if (!used[i] && getBallColor(i) != oddColor) {
|
||||
order.add(i);
|
||||
used[i] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
TELE.addData("works", order);
|
||||
TELE.addData("oddBall", oddColor);
|
||||
shootAll = true;
|
||||
|
||||
}
|
||||
|
||||
void addOddLast(List<Integer> order, boolean oddColor) {
|
||||
// Odd ball last
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||
TELE.addData("1", shootOrder);
|
||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||
TELE.addData("works", shootOrder);
|
||||
TELE.addData("oddBall", oddColor);
|
||||
shootAll = true;
|
||||
|
||||
}
|
||||
|
||||
// Returns color of ball in slot i (1-based)
|
||||
boolean getBallColor(int slot) {
|
||||
switch (slot) {
|
||||
case 1: return green1;
|
||||
case 2: return green2;
|
||||
case 3: return green3;
|
||||
case 1:
|
||||
return green1;
|
||||
case 2:
|
||||
return green2;
|
||||
case 3:
|
||||
return green3;
|
||||
}
|
||||
return false; // default
|
||||
}
|
||||
|
||||
boolean ballIn(int slot) {
|
||||
switch (slot) {
|
||||
case 1:
|
||||
|
||||
if (!s1T.isEmpty()) {
|
||||
|
||||
return !(s1T.get(s1T.size() - 1) < (getRuntime()) - 3);
|
||||
}
|
||||
|
||||
case 2:
|
||||
|
||||
if (!s2T.isEmpty()) {
|
||||
|
||||
return !(s2T.get(s2T.size() - 1) < (getRuntime()) - 3);
|
||||
}
|
||||
|
||||
case 3:
|
||||
|
||||
if (!s3T.isEmpty()) {
|
||||
|
||||
return !(s3T.get(s3T.size() - 1) < (getRuntime()) - 3);
|
||||
|
||||
}
|
||||
}
|
||||
return true; // default
|
||||
}
|
||||
|
||||
public double turretPos() {
|
||||
return (scalar*((robot.turr1Pos.getVoltage()-restPos) /3.3 ));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -0,0 +1,92 @@
|
||||
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.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
|
||||
public class Flywheel {
|
||||
Robot robot;
|
||||
|
||||
MultipleTelemetry TELE;
|
||||
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 prevSteady = false;
|
||||
double velo = 0.0;
|
||||
double prevVelo = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
double powPID = 0.0;
|
||||
boolean steady = false;
|
||||
|
||||
public Flywheel () {
|
||||
//robot = new Robot(hardwareMap);
|
||||
}
|
||||
|
||||
public double getVelo () {
|
||||
return velo;
|
||||
}
|
||||
|
||||
public boolean getSteady() {
|
||||
return steady;
|
||||
}
|
||||
|
||||
private double getTimeSeconds ()
|
||||
{
|
||||
return (double) System.currentTimeMillis()/1000.0;
|
||||
}
|
||||
|
||||
|
||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||
targetVelocity = (double) commandedVelocity;
|
||||
|
||||
ticker++;
|
||||
if (ticker % 8 == 0) {
|
||||
currentPos = shooter1CurPos / 2048;
|
||||
stamp = getTimeSeconds(); //getRuntime();
|
||||
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||
initPos = currentPos;
|
||||
stamp1 = stamp;
|
||||
}
|
||||
// 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));
|
||||
}
|
||||
|
||||
// really should be a running average of the last 5
|
||||
if ((Math.abs(targetVelocity - velo) < 150.0) && (Math.abs(targetVelocity - prevVelo) < 150.0))
|
||||
{
|
||||
steady = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
steady = false;
|
||||
}
|
||||
|
||||
return powPID;
|
||||
}
|
||||
|
||||
public void update()
|
||||
{
|
||||
};
|
||||
};
|
||||
@@ -17,7 +17,7 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
public static double hoodPos = 0.501;
|
||||
|
||||
public static double scalar = 1.112;
|
||||
public static double restPos = 0.158;
|
||||
public static double restPos = 0.15;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
Reference in New Issue
Block a user