Compare commits
11 Commits
e8bf2033ad
...
SpindexerP
| Author | SHA1 | Date | |
|---|---|---|---|
| e7dfa11196 | |||
| 51bf55cc49 | |||
| 6f3a178a08 | |||
| ccb52f625d | |||
| 8f92dc8f31 | |||
| 40d51ce757 | |||
| cfd09df8a0 | |||
| 59796154bd | |||
| d42af20447 | |||
| 1c292e77c7 | |||
| fde0880225 |
@@ -1,43 +1,48 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
@@ -48,6 +53,7 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferSe
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_blueClose;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_redClose;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.AUTO_CLOSE_VEL;
|
||||
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinPow;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
@@ -60,6 +66,7 @@ import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
@@ -69,7 +76,7 @@ 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.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
|
||||
@@ -82,15 +89,17 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
public static double intake2Time = 3.0;
|
||||
public static double colorDetect = 3.0;
|
||||
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||
public static double slowSpeed = 30.0;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
FlywheelV2 flywheel;
|
||||
Flywheel flywheel;
|
||||
Servos servo;
|
||||
double velo = 0.0;
|
||||
boolean gpp = false;
|
||||
boolean pgp = false;
|
||||
boolean ppg = false;
|
||||
public static double spinUnjamTime = 0.6;
|
||||
double powPID = 0.0;
|
||||
double bearing = 0.0;
|
||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||
@@ -100,10 +109,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
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);
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.update();
|
||||
@@ -171,10 +178,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
@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);
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
@@ -207,6 +212,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
boolean zeroPassed = false;
|
||||
double currentPos = 0.0;
|
||||
double prevPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
@@ -214,68 +220,86 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
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);
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(-0.3);
|
||||
|
||||
if (ticker == 1) {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
initPos = servo.getSpinPos();
|
||||
|
||||
finalPos = initPos + 0.6;
|
||||
|
||||
if (finalPos > 1.0) {
|
||||
finalPos = finalPos - 1;
|
||||
zeroNeeded = true;
|
||||
} else if (finalPos > 0.95) {
|
||||
finalPos = 0.0;
|
||||
zeroNeeded = true;
|
||||
}
|
||||
currentPos = initPos;
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (ticker > 16) {
|
||||
robot.spin1.setPower(0.08);
|
||||
robot.spin2.setPower(-0.08);
|
||||
}
|
||||
robot.intake.setPower(0);
|
||||
|
||||
if (getRuntime() - stamp < 2.7) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
return true;
|
||||
|
||||
prevPos = currentPos;
|
||||
currentPos = servo.getSpinPos();
|
||||
if (zeroNeeded) {
|
||||
if (currentPos - prevPos < -0.5) {
|
||||
zeroPassed = true;
|
||||
}
|
||||
if (zeroPassed) {
|
||||
if (currentPos > finalPos) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
if (currentPos > finalPos) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action spindexUnjam(double jamTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
|
||||
|
||||
ticker++;
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
|
||||
if (ticker % 12 < 6) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
}
|
||||
|
||||
if (getRuntime() - stamp > jamTime+0.4) {
|
||||
|
||||
robot.intake.setPower(0.5);
|
||||
|
||||
return false;
|
||||
}
|
||||
else if (getRuntime() - stamp > jamTime) {
|
||||
|
||||
robot.intake.setPower(-(getRuntime()-stamp-jamTime)*2.5);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
else {
|
||||
robot.intake.setPower(1);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
@@ -291,17 +315,22 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
}
|
||||
ticker++;
|
||||
|
||||
if (ticker % 12 < 3) {
|
||||
if (ticker % 60 < 12) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else if (reverse) {
|
||||
} else if (ticker % 60 < 30) {
|
||||
robot.spin1.setPower(-0.5);
|
||||
robot.spin2.setPower(0.5);
|
||||
}
|
||||
else if (ticker % 60 < 42) {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
} else {
|
||||
robot.spin1.setPower(-0.15);
|
||||
robot.spin2.setPower(0.15);
|
||||
}
|
||||
else {
|
||||
robot.spin1.setPower(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
}
|
||||
robot.intake.setPower(1);
|
||||
TELE.addData("Reverse?", reverse);
|
||||
@@ -319,9 +348,10 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
} else {
|
||||
if (ticker % 4 == 0) {
|
||||
spinCurrentPos = servo.getSpinPos();
|
||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.02;
|
||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
||||
spinInitPos = spinCurrentPos;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@@ -340,10 +370,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
}
|
||||
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);
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||
@@ -418,7 +446,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
flywheel = new FlywheelV2();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -438,24 +466,27 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
//
|
||||
// TrajectoryActionBuilder lever = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
// .strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
||||
|
||||
TrajectoryActionBuilder lever = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
||||
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2c, by2c, bh2c))
|
||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b);
|
||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
TrajectoryActionBuilder shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
@@ -471,6 +502,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
if (gamepad2.crossWasPressed()) {
|
||||
redAlliance = !redAlliance;
|
||||
|
||||
}
|
||||
|
||||
double turretPID;
|
||||
@@ -482,26 +514,29 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
||||
// lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
// .strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(rx2c, ry2c, rh2c))
|
||||
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
pickup3 = drive.actionBuilder(new Pose2d(rx1,ry1, rh1))
|
||||
pickup3 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||
.strafeToLinearHeading(new Vector2d(rx4a, ry4a), rh4a)
|
||||
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b);
|
||||
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
shoot3 = drive.actionBuilder(new Pose2d(rx4b, ry4b, rh4b))
|
||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||
|
||||
} else {
|
||||
turretPID = turret_blueClose;
|
||||
@@ -511,17 +546,26 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot1 = drive.actionBuilder(new Pose2d(bx2c, by2c, bh2c))
|
||||
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);
|
||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
|
||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
|
||||
pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||
new TranslationalVelConstraint(slowSpeed));
|
||||
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turretPID);
|
||||
@@ -573,8 +617,9 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
Actions.runBlocking(
|
||||
new SequentialAction(
|
||||
lever.build(),
|
||||
shoot1.build()
|
||||
shoot1.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
@@ -604,7 +649,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot2.build()
|
||||
shoot2.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
)
|
||||
);
|
||||
|
||||
@@ -630,7 +676,9 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot3.build()
|
||||
shoot3.build(),
|
||||
spindexUnjam(spinUnjamTime)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
|
||||
@@ -14,28 +14,28 @@ public class Poses {
|
||||
|
||||
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||
|
||||
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
||||
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
||||
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||
public static double rx1 = 40, ry1 = -7, rh1 = 0;
|
||||
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
||||
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140);
|
||||
|
||||
public static double rx2c = 34, ry2c = 50, rh2c = 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 rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
||||
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
|
||||
|
||||
public static double rx4a = 71, ry4a = 60, rh4a = Math.toRadians(140);
|
||||
public static double rx4b = 79, ry4b = 79, rh4b = Math.toRadians(140);
|
||||
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
|
||||
|
||||
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
||||
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
||||
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||
public static double bx2c = 40, by2c = -50, bh2c = Math.toRadians(-140);
|
||||
public static double bx1 = 40, by1 = 7, bh1 = 0;
|
||||
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140);
|
||||
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140);
|
||||
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140);
|
||||
|
||||
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
||||
|
||||
public static double bx4a = 69, by4a = -60, bh4a = Math.toRadians(-140);
|
||||
public static double bx4b = 75, by4b = -79, bh4b = Math.toRadians(-140);
|
||||
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||
|
||||
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||
|
||||
@@ -5,16 +5,16 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
public class ServoPositions {
|
||||
|
||||
public static double spindexer_intakePos1 = 0.39;
|
||||
public static double spindexer_intakePos1 = 0.19;
|
||||
|
||||
public static double spindexer_intakePos2 = 0.5;
|
||||
public static double spindexer_intakePos2 = 0.35;//0.5;
|
||||
|
||||
public static double spindexer_intakePos3 = 0.66;
|
||||
public static double spindexer_intakePos3 = 0.51;//0.66;
|
||||
|
||||
public static double spindexer_outtakeBall3 = 0.42;
|
||||
public static double spindexer_outtakeBall3 = 0.47;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.74;
|
||||
public static double spindexer_outtakeBall1 = 0.58;
|
||||
public static double spindexer_outtakeBall2 = 0.31;
|
||||
public static double spindexer_outtakeBall1 = 0.15;
|
||||
|
||||
public static double transferServo_out = 0.15;
|
||||
|
||||
@@ -24,7 +24,7 @@ public class ServoPositions {
|
||||
|
||||
public static double hoodDefault = 0.6;
|
||||
|
||||
public static double hoodAuto = 0.55;
|
||||
public static double hoodAuto = 0.27;
|
||||
|
||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
||||
|
||||
|
||||
@@ -19,6 +19,6 @@ public class ShooterVars {
|
||||
public static double maxStep = 0.06; // prevents sudden jumps
|
||||
|
||||
// VELOCITY CONSTANTS
|
||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||
}
|
||||
@@ -129,7 +129,7 @@ public class TeleopV2 extends LinearOpMode {
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
servo = new Servos(hardwareMap);
|
||||
flywheel = new Flywheel();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
|
||||
@@ -282,12 +282,9 @@ public class TeleopV2 extends LinearOpMode {
|
||||
|
||||
//SHOOTER:
|
||||
|
||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
||||
double powPID = flywheel.manageFlywheel((int) vel);
|
||||
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
//TURRET:
|
||||
|
||||
|
||||
@@ -21,6 +21,7 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
@@ -28,9 +29,10 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
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.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
@@ -45,10 +47,10 @@ public class TeleopV3 extends LinearOpMode {
|
||||
public static double shootStamp2 = 0.0;
|
||||
public static double spinningPow = 0.2;
|
||||
public static double spindexPos = spindexer_intakePos1;
|
||||
public static double spinPow = 0.08;
|
||||
public static double bMult = -1, bDiv = 130000;
|
||||
public static double spinPow = 0.09;
|
||||
public static double bMult = 1, bDiv = 2200;
|
||||
public static double tp = 0.8, ti = 0.001, td = 0.0315, tf = 0;
|
||||
public static boolean manualTurret = false;
|
||||
public static boolean manualTurret = true;
|
||||
public double vel = 3000;
|
||||
public boolean autoVel = true;
|
||||
public double manualOffset = 0.0;
|
||||
@@ -67,8 +69,9 @@ public class TeleopV3 extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Servos servo;
|
||||
FlywheelV2 flywheel;
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
Spindexer spindexer;
|
||||
double autoHoodOffset = 0.0;
|
||||
|
||||
int shooterTicker = 0;
|
||||
@@ -93,7 +96,8 @@ public class TeleopV3 extends LinearOpMode {
|
||||
boolean shootA = true;
|
||||
boolean shootB = true;
|
||||
boolean shootC = true;
|
||||
boolean autoSpintake = true;
|
||||
boolean autoSpintake = false;
|
||||
boolean enableSpindexerManager = true;
|
||||
List<Integer> shootOrder = new ArrayList<>();
|
||||
boolean outtake1 = false;
|
||||
boolean outtake2 = false;
|
||||
@@ -139,15 +143,14 @@ public class TeleopV3 extends LinearOpMode {
|
||||
robot = new Robot(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
servo = new Servos(hardwareMap);
|
||||
flywheel = new FlywheelV2();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
PIDFController tController = new PIDFController(tp, ti, td, tf);
|
||||
|
||||
tController.setTolerance(0.001);
|
||||
|
||||
|
||||
|
||||
if (redAlliance) {
|
||||
robot.limelight.pipelineSwitch(3);
|
||||
} else {
|
||||
@@ -234,31 +237,24 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
if (gamepad1.right_bumper) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
intakeTicker++;
|
||||
|
||||
if (intakeTicker % 4 == 0) {
|
||||
spinCurrentPos = servo.getSpinPos();
|
||||
if (Math.abs(spinCurrentPos - spinInitPos) < 0.02) {
|
||||
reverse = true;
|
||||
} else {
|
||||
reverse = false;
|
||||
}
|
||||
spinInitPos = spinCurrentPos;
|
||||
}
|
||||
|
||||
if (intakeTicker % 12 < 3) {
|
||||
if (intakeTicker % 20 < 2) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else if (reverse) {
|
||||
} else if (intakeTicker % 20 < 10) {
|
||||
robot.spin1.setPower(-0.5);
|
||||
robot.spin2.setPower(0.5);
|
||||
} else if (intakeTicker % 20 < 12) {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
} else {
|
||||
robot.spin1.setPower(-spinningPow);
|
||||
robot.spin2.setPower(spinningPow);
|
||||
robot.spin1.setPower(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
}
|
||||
|
||||
robot.intake.setPower(1);
|
||||
intakeStamp = getRuntime();
|
||||
TELE.addData("Reverse?", reverse);
|
||||
@@ -386,7 +382,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
||||
|
||||
desiredTurretAngle += manualOffset;
|
||||
desiredTurretAngle += manualOffset + error;
|
||||
|
||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||
|
||||
@@ -406,13 +402,9 @@ public class TeleopV3 extends LinearOpMode {
|
||||
pos = 0.83;
|
||||
}
|
||||
|
||||
|
||||
//SHOOTER:
|
||||
|
||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
|
||||
robot.shooter1.setPower(powPID);
|
||||
robot.shooter2.setPower(powPID);
|
||||
flywheel.manageFlywheel(vel);
|
||||
|
||||
//VELOCITY AUTOMATIC
|
||||
|
||||
@@ -440,67 +432,56 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//TODO: test the camera teleop code
|
||||
|
||||
|
||||
TELE.addData("posS2", pos);
|
||||
|
||||
// if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
|
||||
// double bearing;
|
||||
//
|
||||
// LLResult result = robot.limelight.getLatestResult();
|
||||
// if (result != null) {
|
||||
// if (result.isValid()) {
|
||||
// bearing = result.getTx() * bMult;
|
||||
// overrideTurr = true;
|
||||
//
|
||||
// double bearingCorrection = bearing / bDiv;
|
||||
//
|
||||
// // deadband: ignore tiny noise
|
||||
// if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
||||
//
|
||||
// error += bearingCorrection;
|
||||
//
|
||||
// }
|
||||
// camTicker++;
|
||||
// TELE.addData("tx", bearing);
|
||||
// TELE.addData("ty", result.getTy());
|
||||
// }
|
||||
// }
|
||||
//
|
||||
// } else {
|
||||
// camTicker = 0;
|
||||
// overrideTurr = false;
|
||||
// }
|
||||
if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
|
||||
double bearing;
|
||||
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
bearing = result.getTx() * bMult;
|
||||
|
||||
double bearingCorrection = bearing / bDiv;
|
||||
|
||||
error += bearingCorrection;
|
||||
|
||||
camTicker++;
|
||||
TELE.addData("tx", bearingCorrection);
|
||||
TELE.addData("ty", result.getTy());
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
camTicker = 0;
|
||||
overrideTurr = false;
|
||||
}
|
||||
|
||||
if (!overrideTurr) {
|
||||
turretPos = pos;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
TELE.addData("posS3", turretPos);
|
||||
|
||||
if (manualTurret) {
|
||||
pos = turrDefault + (manualOffset / 100);
|
||||
pos = turrDefault + (manualOffset / 100) + error;
|
||||
}
|
||||
|
||||
if (!overrideTurr) {
|
||||
turretPos = pos;
|
||||
}
|
||||
|
||||
if (gamepad2.dpad_right || gamepad1.dpad_right) {
|
||||
manualOffset -= 2;
|
||||
} else if (gamepad2.dpad_left || gamepad1.dpad_left) {
|
||||
manualOffset += 2;
|
||||
if (Math.abs(gamepad2.left_stick_x)>0.2) {
|
||||
manualOffset += 1.35 * gamepad2.left_stick_x;
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1-pos);
|
||||
robot.turr2.setPosition(1 - pos);
|
||||
|
||||
//HOOD:
|
||||
|
||||
if (autoHood) {
|
||||
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
||||
robot.hood.setPosition(0.15 + hoodOffset);
|
||||
} else {
|
||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||
}
|
||||
@@ -518,7 +499,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
if (gamepad2.cross) {
|
||||
manualOffset = 0;
|
||||
fixedTurret = true;
|
||||
overrideTurr = true;
|
||||
}
|
||||
|
||||
if (gamepad2.squareWasPressed()) {
|
||||
@@ -552,26 +533,45 @@ public class TeleopV3 extends LinearOpMode {
|
||||
// }
|
||||
// }
|
||||
|
||||
if (gamepad1.leftBumperWasPressed()) {
|
||||
if (gamepad1.left_bumper && !enableSpindexerManager) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
autoSpintake = false;
|
||||
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
intakeTicker++;
|
||||
|
||||
if (intakeTicker % 10 < 1) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} else if (intakeTicker % 10 < 5) {
|
||||
robot.spin1.setPower(-0.5);
|
||||
robot.spin2.setPower(0.5);
|
||||
} else if (intakeTicker % 10 < 6) {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
} else {
|
||||
robot.spin1.setPower(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
}
|
||||
|
||||
intake = false;
|
||||
reject = false;
|
||||
|
||||
robot.intake.setPower(0.5);
|
||||
|
||||
}
|
||||
|
||||
if (gamepad1.leftBumperWasReleased()) {
|
||||
if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) {
|
||||
shootStamp = getRuntime();
|
||||
shootAll = true;
|
||||
spindexPos = spindexer_intakePos1;
|
||||
|
||||
shooterTicker = 0;
|
||||
}
|
||||
|
||||
if (shootAll) {
|
||||
if (shootAll && !enableSpindexerManager) {
|
||||
|
||||
TELE.addData("100% works", shootOrder);
|
||||
|
||||
@@ -603,6 +603,127 @@ public class TeleopV3 extends LinearOpMode {
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (enableSpindexerManager) {
|
||||
if (!shootAll) {
|
||||
spindexer.processIntake();
|
||||
}
|
||||
|
||||
// RIGHT_BUMPER
|
||||
if (gamepad1.right_bumper) {
|
||||
robot.intake.setPower(1);
|
||||
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
}
|
||||
|
||||
// LEFT_BUMPER
|
||||
if (!shootAll &&
|
||||
(gamepad1.leftBumperWasReleased() ||
|
||||
gamepad1.leftBumperWasPressed() ||
|
||||
gamepad1.left_bumper)) {
|
||||
shootStamp = getRuntime();
|
||||
shootAll = true;
|
||||
|
||||
shooterTicker = 0;
|
||||
}
|
||||
|
||||
if (shootAll) {
|
||||
|
||||
intake = false;
|
||||
reject = false;
|
||||
|
||||
shooterTicker++;
|
||||
|
||||
// TODO: Change starting position based on desired order to shoot green ball
|
||||
spindexPos = spindexer_intakePos1;
|
||||
|
||||
if (getRuntime() - shootStamp < 3.5) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
shootAll = false;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//
|
||||
// if (shootAll) {
|
||||
//
|
||||
// TELE.addData("100% works", shootOrder);
|
||||
//
|
||||
// intake = false;
|
||||
// reject = false;
|
||||
//
|
||||
// shooterTicker++;
|
||||
//
|
||||
// spindexPos = spindexer_intakePos1;
|
||||
//
|
||||
// if (getRuntime() - shootStamp < 1) {
|
||||
//
|
||||
// if (servo.spinEqual(spindexer_outtakeBall3) || ((getRuntime()-shootStamp)>0.4)){
|
||||
// robot.transferServo.setPosition(transferServo_in);
|
||||
//
|
||||
// } else {
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
//
|
||||
// }
|
||||
//
|
||||
//
|
||||
// autoSpintake = true;
|
||||
//
|
||||
// spindexPos = spindexer_outtakeBall3;
|
||||
// robot.intake.setPower(0.5);
|
||||
//
|
||||
// }
|
||||
//
|
||||
// else if (getRuntime() - shootStamp < 1.8) {
|
||||
//
|
||||
// robot.transferServo.setPosition(transferServo_in);
|
||||
//
|
||||
// autoSpintake = true;
|
||||
// robot.intake.setPower(0);
|
||||
//
|
||||
// spindexPos = spindexer_outtakeBall2;
|
||||
//
|
||||
// }
|
||||
// else if (getRuntime() - shootStamp < 2.6) {
|
||||
//
|
||||
// robot.transferServo.setPosition(transferServo_in);
|
||||
//
|
||||
// autoSpintake = false;
|
||||
//
|
||||
// robot.spin1.setPower(1);
|
||||
// robot.spin2.setPower(-1);
|
||||
//
|
||||
// }
|
||||
//
|
||||
// else {
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
// spindexPos = spindexer_intakePos1;
|
||||
//
|
||||
// shootAll = false;
|
||||
//
|
||||
// autoSpintake = true;
|
||||
//
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
// }
|
||||
//
|
||||
// }
|
||||
|
||||
// if (gamepad1.squareWasPressed()) {
|
||||
// square = true;
|
||||
// shootStamp = getRuntime();
|
||||
@@ -705,7 +826,6 @@ public class TeleopV3 extends LinearOpMode {
|
||||
// }
|
||||
|
||||
//EXTRA STUFFINESS:
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
for (LynxModule hub : allHubs) {
|
||||
@@ -721,15 +841,20 @@ public class TeleopV3 extends LinearOpMode {
|
||||
TELE.addData("distanceToGoal", distanceToGoal);
|
||||
TELE.addData("hood", robot.hood.getPosition());
|
||||
TELE.addData("targetVel", vel);
|
||||
TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()));
|
||||
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("shootOrder", shootOrder);
|
||||
TELE.addData("oddColor", oddBallColor);
|
||||
|
||||
TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1));
|
||||
TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition);
|
||||
TELE.addData("spinIntakeState", spindexer.currentIntakeState);
|
||||
TELE.addData("spinTestCounter", spindexer.counter);
|
||||
TELE.addData("autoSpintake", autoSpintake);
|
||||
TELE.addData("distanceRearCenter", spindexer.distanceRearCenter);
|
||||
TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver);
|
||||
TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger);
|
||||
TELE.addData("shootall commanded", shootAll);
|
||||
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||
|
||||
TELE.update();
|
||||
|
||||
ticker++;
|
||||
|
||||
@@ -20,7 +20,7 @@ public class LimelightTest extends LinearOpMode {
|
||||
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "Limelight");
|
||||
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
limelight.pipelineSwitch(pipeline);
|
||||
waitForStart();
|
||||
|
||||
@@ -9,7 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@Config
|
||||
@@ -21,12 +21,17 @@ public class ShooterTest extends LinearOpMode {
|
||||
// --- CONSTANTS YOU TUNE ---
|
||||
|
||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||
public static double Velocity = 0.0;
|
||||
public static double P = 40.0;
|
||||
public static double I = 0.3;
|
||||
public static double D = 7.0;
|
||||
public static double F = 10.0;
|
||||
public static double transferPower = 1.0;
|
||||
public static double hoodPos = 0.501;
|
||||
public static double turretPos = 0.501;
|
||||
public static boolean shoot = false;
|
||||
Robot robot;
|
||||
FlywheelV2 flywheel;
|
||||
Flywheel flywheel;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
@@ -34,7 +39,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
robot = new Robot(hardwareMap);
|
||||
DcMotorEx leftShooter = robot.shooter1;
|
||||
DcMotorEx rightShooter = robot.shooter2;
|
||||
flywheel = new FlywheelV2();
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -50,10 +55,8 @@ public class ShooterTest extends LinearOpMode {
|
||||
rightShooter.setPower(parameter);
|
||||
leftShooter.setPower(parameter);
|
||||
} else if (mode == 1) {
|
||||
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||
rightShooter.setPower(powPID);
|
||||
leftShooter.setPower(powPID);
|
||||
TELE.addData("PIDPower", powPID);
|
||||
flywheel.setPIDF(P,I,D,F);
|
||||
flywheel.manageFlywheel((int) Velocity);
|
||||
}
|
||||
|
||||
if (hoodPos != 0.501) {
|
||||
@@ -67,7 +70,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
}
|
||||
TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()));
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Velocity 1", flywheel.getVelo1());
|
||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||
TELE.addData("Power", robot.shooter1.getPower());
|
||||
|
||||
@@ -2,6 +2,9 @@ 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.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
|
||||
@@ -17,72 +20,65 @@ public class Flywheel {
|
||||
double velo = 0.0;
|
||||
double velo1 = 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 Flywheel () {
|
||||
//robot = new Robot(hardwareMap);
|
||||
public Flywheel (HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
}
|
||||
|
||||
public double getVelo () {
|
||||
return velo;
|
||||
}
|
||||
public double getVelo1 () {
|
||||
return velo1;
|
||||
}
|
||||
public double getVelo2 () {
|
||||
return velo2;
|
||||
}
|
||||
|
||||
public boolean getSteady() {
|
||||
return steady;
|
||||
}
|
||||
|
||||
// Set the robot PIDF for the next cycle.
|
||||
public void setPIDF(double p, double i, double d, double f) {
|
||||
robot.shooterPIDF.p = p;
|
||||
robot.shooterPIDF.i = i;
|
||||
robot.shooterPIDF.d = d;
|
||||
robot.shooterPIDF.f = f;
|
||||
}
|
||||
private double getTimeSeconds ()
|
||||
{
|
||||
return (double) System.currentTimeMillis()/1000.0;
|
||||
}
|
||||
|
||||
// Convert from RPM to Ticks per Second
|
||||
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
||||
|
||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||
// Convert from Ticks per Second to RPM
|
||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||
|
||||
public double manageFlywheel(double commandedVelocity) {
|
||||
targetVelocity = commandedVelocity;
|
||||
|
||||
ticker++;
|
||||
if (ticker % 2 == 0) {
|
||||
velo5 = velo4;
|
||||
velo4 = velo3;
|
||||
velo3 = velo2;
|
||||
velo2 = velo1;
|
||||
// Turn PIDF for Target Velocities
|
||||
//robot.shooterPIDF.p = P;
|
||||
//robot.shooterPIDF.i = I;
|
||||
//robot.shooterPIDF.d = D;
|
||||
//robot.shooterPIDF.f = F;
|
||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
|
||||
currentPos = shooter1CurPos / 2048;
|
||||
stamp = getTimeSeconds(); //getRuntime();
|
||||
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||
initPos = currentPos;
|
||||
stamp1 = stamp;
|
||||
|
||||
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
||||
}
|
||||
// Flywheel control code here
|
||||
if (targetVelocity - velo > 500) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - targetVelocity > 500){
|
||||
powPID = 0.0;
|
||||
} else {
|
||||
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = targetVelocity - velo;
|
||||
double correction = kP * error;
|
||||
|
||||
// limit how fast power changes (prevents oscillation)
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
}
|
||||
// Record Current Velocity
|
||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||
velo2 = TPS_to_RPM(robot.shooter1.getVelocity()); // Possible error: should it be shooter2 not shooter1?
|
||||
velo = Math.max(velo1,velo2);
|
||||
|
||||
// really should be a running average of the last 5
|
||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
||||
|
||||
return powPID;
|
||||
}
|
||||
@@ -90,4 +86,4 @@ public class Flywheel {
|
||||
public void update()
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -8,6 +8,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||
@@ -23,6 +24,13 @@ public class Robot {
|
||||
public DcMotorEx backRight;
|
||||
public DcMotorEx intake;
|
||||
public DcMotorEx transfer;
|
||||
public PIDFCoefficients shooterPIDF;
|
||||
public double shooterPIDF_P = 10.0;
|
||||
public double shooterPIDF_I = 0.6;
|
||||
public double shooterPIDF_D = 5.0;
|
||||
public double shooterPIDF_F = 10.0;
|
||||
|
||||
public double[] shooterPIDF_StepSizes = {10.0,1.0,0.001, 0.0001};
|
||||
public DcMotorEx shooter1;
|
||||
public DcMotorEx shooter2;
|
||||
public Servo hood;
|
||||
@@ -69,8 +77,11 @@ public class Robot {
|
||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
shooterPIDF = new PIDFCoefficients(shooterPIDF_P,shooterPIDF_I , shooterPIDF_D, shooterPIDF_F);
|
||||
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
|
||||
hood = hardwareMap.get(Servo.class, "hood");
|
||||
|
||||
|
||||
@@ -0,0 +1,400 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
|
||||
public class Spindexer {
|
||||
Robot robot;
|
||||
Servos servos;
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
double lastKnownSpinPos = 0.0;
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||
|
||||
double spinCurrentPos = 0.0;
|
||||
|
||||
public int commandedIntakePosition = 0;
|
||||
|
||||
public double distanceRearCenter = 0.0;
|
||||
public double distanceFrontDriver = 0.0;
|
||||
public double distanceFrontPassenger = 0.0;
|
||||
|
||||
// For Use
|
||||
enum RotatedBallPositionNames {
|
||||
REARCENTER,
|
||||
FRONTDRIVER,
|
||||
FRONTPASSENGER
|
||||
}
|
||||
// Array of commandedIntakePositions with contents
|
||||
// {RearCenter, FrontDriver, FrontPassenger}
|
||||
static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}};
|
||||
class spindexerBallRoatation {
|
||||
int rearCenter = 0; // aka commanded Position
|
||||
int frontDriver = 0;
|
||||
int frontPassenger = 0;
|
||||
}
|
||||
|
||||
enum IntakeState {
|
||||
UNKNOWN,
|
||||
INTAKE,
|
||||
FINDNEXT,
|
||||
MOVING,
|
||||
FULL,
|
||||
SHOOTNEXT,
|
||||
SHOOTMOVING,
|
||||
SHOOTWAIT,
|
||||
};
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN;
|
||||
|
||||
enum BallColor {
|
||||
UNKNOWN,
|
||||
GREEN,
|
||||
PURPLE
|
||||
};
|
||||
|
||||
class BallPosition {
|
||||
boolean isEmpty = true;
|
||||
int foundEmpty = 0;
|
||||
BallColor ballColor = BallColor.UNKNOWN;
|
||||
}
|
||||
|
||||
BallPosition[] ballPositions = new BallPosition[3];
|
||||
|
||||
public boolean init () {
|
||||
return true;
|
||||
}
|
||||
|
||||
public Spindexer(HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
servos = new Servos(hardwareMap);
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
//TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
|
||||
lastKnownSpinPos = servos.getSpinPos();
|
||||
|
||||
ballPositions[0] = new BallPosition();
|
||||
ballPositions[1] = new BallPosition();
|
||||
ballPositions[2] = new BallPosition();
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
double[] outakePositions =
|
||||
{spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3};
|
||||
|
||||
double[] intakePositions =
|
||||
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
||||
|
||||
public int counter = 0;
|
||||
|
||||
// private double getTimeSeconds ()
|
||||
// {
|
||||
// return (double) System.currentTimeMillis()/1000.0;
|
||||
// }
|
||||
|
||||
// public double getPos() {
|
||||
// robot.spin1Pos.getVoltage();
|
||||
// robot.spin1Pos.getMaxVoltage();
|
||||
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
||||
// }
|
||||
|
||||
// public void manageSpindexer() {
|
||||
//
|
||||
// }
|
||||
|
||||
public void resetBallPosition (int pos) {
|
||||
ballPositions[pos].isEmpty = true;
|
||||
ballPositions[pos].foundEmpty = 0;
|
||||
ballPositions[pos].ballColor = BallColor.UNKNOWN;
|
||||
}
|
||||
|
||||
public void resetSpindexer () {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
resetBallPosition(i);
|
||||
}
|
||||
currentIntakeState = IntakeState.UNKNOWN;
|
||||
}
|
||||
|
||||
// Detects if a ball is found and what color.
|
||||
// Returns true is there was a new ball found in Position 1
|
||||
// FIXIT: Reduce number of times that we read the color sensors for loop times.
|
||||
public boolean detectBalls() {
|
||||
|
||||
boolean newPos1Detection = false;
|
||||
int spindexerBallPos = 0;
|
||||
|
||||
// Read Distances
|
||||
distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||
distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||
distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||
|
||||
// Position 1
|
||||
if (distanceRearCenter < 43) {
|
||||
|
||||
// Mark Ball Found
|
||||
newPos1Detection = true;
|
||||
|
||||
// Detect which color
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
// FIXIT - Add filtering to improve accuracy.
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
// Position 2
|
||||
// Find which ball position this is in the spindexer
|
||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||
if (distanceFrontDriver < 60) {
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
// FIXIT: Comment out for now due to loop time concerns
|
||||
// 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; // purple
|
||||
// } else {
|
||||
// b2 = 1; // green
|
||||
// }
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
resetBallPosition(spindexerBallPos);
|
||||
}
|
||||
ballPositions[spindexerBallPos].foundEmpty++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Position 3
|
||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
|
||||
if (distanceFrontPassenger < 33) {
|
||||
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
// FIXIT: Comment out for now due to loop time concerns
|
||||
// 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; // purple
|
||||
// } else {
|
||||
// b3 = 1; // green
|
||||
// }
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
resetBallPosition(spindexerBallPos);
|
||||
}
|
||||
ballPositions[spindexerBallPos].foundEmpty++;
|
||||
}
|
||||
}
|
||||
|
||||
// TELE.addData("Velocity", velo);
|
||||
// TELE.addLine("Detecting");
|
||||
// TELE.addData("Distance 1", s1D);
|
||||
// TELE.addData("Distance 2", s2D);
|
||||
// TELE.addData("Distance 3", s3D);
|
||||
// TELE.addData("B1", b1);
|
||||
// TELE.addData("B2", b2);
|
||||
// TELE.addData("B3", b3);
|
||||
// TELE.update();
|
||||
|
||||
return newPos1Detection;
|
||||
}
|
||||
|
||||
public void moveSpindexerToPos(double pos) {
|
||||
spinCurrentPos = servos.getSpinPos();
|
||||
|
||||
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
||||
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
}
|
||||
|
||||
public void stopSpindexer() {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
}
|
||||
|
||||
public boolean isFull () {
|
||||
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
||||
}
|
||||
public boolean processIntake() {
|
||||
|
||||
switch (currentIntakeState) {
|
||||
case UNKNOWN:
|
||||
// For now just set position ONE if UNKNOWN
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(intakePositions[0]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
break;
|
||||
case INTAKE:
|
||||
// Ready for intake and Detecting a New Ball
|
||||
if (detectBalls()) {
|
||||
ballPositions[commandedIntakePosition].isEmpty = false;
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
} else {
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
case FINDNEXT:
|
||||
// Find Next Open Position and start movement
|
||||
double currentSpindexerPos = servos.getSpinPos();
|
||||
double commandedtravelDistance = 2.0;
|
||||
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 1
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 2
|
||||
commandedIntakePosition = 1;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||
// Position 3
|
||||
commandedIntakePosition = 2;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
commandedtravelDistance = proposedTravelDistance;
|
||||
}
|
||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||
// Full
|
||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||
}
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case MOVING:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls();
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
|
||||
case FULL:
|
||||
// Double Check Colors
|
||||
detectBalls();
|
||||
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
||||
// Error handling found an empty spot, get it ready for a ball
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case SHOOTNEXT:
|
||||
// Find Next Open Position and start movement
|
||||
if (!ballPositions[0].isEmpty) {
|
||||
// Position 1
|
||||
commandedIntakePosition = 0;
|
||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty?
|
||||
// Position 2
|
||||
commandedIntakePosition = 1;
|
||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty?
|
||||
// Position 3
|
||||
commandedIntakePosition = 2;
|
||||
servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||
} else {
|
||||
// Empty return to intake state
|
||||
currentIntakeState = IntakeState.FINDNEXT;
|
||||
}
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
break;
|
||||
|
||||
case SHOOTMOVING:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
||||
ballPositions[commandedIntakePosition].isEmpty = true;
|
||||
// Advance to next full position and wait
|
||||
// commandedIntakePosition++;
|
||||
// if (commandedIntakePosition > 2) {
|
||||
// commandedIntakePosition = 0;
|
||||
// }
|
||||
// // Continue moving to next position
|
||||
// servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
// currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
}
|
||||
break;
|
||||
|
||||
case SHOOTWAIT:
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls();
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
// Statements to execute if no case matches
|
||||
}
|
||||
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
||||
//TELE.update();
|
||||
// Signal a successful intake
|
||||
return false;
|
||||
}
|
||||
|
||||
public void update()
|
||||
{
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user