Compare commits
3 Commits
e8bf2033ad
...
d42af20447
| Author | SHA1 | Date | |
|---|---|---|---|
| d42af20447 | |||
| 1c292e77c7 | |||
| fde0880225 |
@@ -1,43 +1,48 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
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.bh2a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
|
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.bh3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3b;
|
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.bx1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2a;
|
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.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.bx3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3b;
|
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.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.by1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by2a;
|
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.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.by3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.by3b;
|
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.rh1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2a;
|
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.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.rh3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3b;
|
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.rx1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2a;
|
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.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.rx3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3b;
|
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.ry1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2a;
|
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.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.ry3a;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3b;
|
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.Poses.teleStart;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_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_blueClose;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_redClose;
|
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.constants.ShooterVars.AUTO_CLOSE_VEL;
|
||||||
|
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinPow;
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
@@ -60,6 +66,7 @@ import com.acmerobotics.roadrunner.ParallelAction;
|
|||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.acmerobotics.roadrunner.SequentialAction;
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
@@ -82,6 +89,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
public static double intake2Time = 3.0;
|
public static double intake2Time = 3.0;
|
||||||
public static double colorDetect = 3.0;
|
public static double colorDetect = 3.0;
|
||||||
public static double holdTurrPow = 0.01; // power to hold turret in place
|
public static double holdTurrPow = 0.01; // power to hold turret in place
|
||||||
|
public static double slowSpeed = 30.0;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
@@ -91,6 +99,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
boolean gpp = false;
|
boolean gpp = false;
|
||||||
boolean pgp = false;
|
boolean pgp = false;
|
||||||
boolean ppg = false;
|
boolean ppg = false;
|
||||||
|
public static double spinUnjamTime = 0.6;
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
double bearing = 0.0;
|
double bearing = 0.0;
|
||||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
@@ -207,6 +216,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
boolean zeroPassed = false;
|
boolean zeroPassed = false;
|
||||||
double currentPos = 0.0;
|
double currentPos = 0.0;
|
||||||
double prevPos = 0.0;
|
double prevPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
@@ -223,55 +233,75 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(-0.3);
|
||||||
|
|
||||||
if (ticker == 1) {
|
if (ticker == 1) {
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
stamp = getRuntime();
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
if (ticker > 16) {
|
robot.intake.setPower(0);
|
||||||
robot.spin1.setPower(0.08);
|
|
||||||
robot.spin2.setPower(-0.08);
|
if (getRuntime() - stamp < 2.7) {
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
|
||||||
|
robot.spin1.setPower(-spinPow);
|
||||||
|
robot.spin2.setPower(spinPow);
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
@@ -291,17 +321,22 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
if (ticker % 12 < 3) {
|
if (ticker % 60 < 12) {
|
||||||
|
|
||||||
robot.spin1.setPower(-1);
|
robot.spin1.setPower(-1);
|
||||||
robot.spin2.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.spin1.setPower(1);
|
||||||
robot.spin2.setPower(-1);
|
robot.spin2.setPower(-1);
|
||||||
} else {
|
}
|
||||||
robot.spin1.setPower(-0.15);
|
else {
|
||||||
robot.spin2.setPower(0.15);
|
robot.spin1.setPower(0.5);
|
||||||
|
robot.spin2.setPower(-0.5);
|
||||||
}
|
}
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
TELE.addData("Reverse?", reverse);
|
TELE.addData("Reverse?", reverse);
|
||||||
@@ -319,9 +354,10 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
if (ticker % 4 == 0) {
|
if (ticker % 4 == 0) {
|
||||||
spinCurrentPos = servo.getSpinPos();
|
spinCurrentPos = servo.getSpinPos();
|
||||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.02;
|
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
||||||
spinInitPos = spinCurrentPos;
|
spinInitPos = spinCurrentPos;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -438,24 +474,27 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
.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))
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2c, by2c, bh2c))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
.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))
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
.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))
|
TrajectoryActionBuilder shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
@@ -471,6 +510,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
if (gamepad2.crossWasPressed()) {
|
||||||
redAlliance = !redAlliance;
|
redAlliance = !redAlliance;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
double turretPID;
|
double turretPID;
|
||||||
@@ -482,26 +522,29 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
.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))
|
// lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
.strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
// .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);
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
.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))
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
.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(rx4a, ry4a), rh4a)
|
||||||
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b);
|
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b,
|
||||||
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
shoot3 = drive.actionBuilder(new Pose2d(rx4b, ry4b, rh4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
turretPID = turret_blueClose;
|
turretPID = turret_blueClose;
|
||||||
@@ -511,17 +554,26 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
.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);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
.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))
|
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
||||||
|
new TranslationalVelConstraint(slowSpeed));
|
||||||
|
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.turr1.setPosition(turretPID);
|
robot.turr1.setPosition(turretPID);
|
||||||
@@ -573,8 +625,9 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new SequentialAction(
|
new SequentialAction(
|
||||||
lever.build(),
|
shoot1.build(),
|
||||||
shoot1.build()
|
spindexUnjam(spinUnjamTime)
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -604,7 +657,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new ParallelAction(
|
new ParallelAction(
|
||||||
shoot2.build()
|
shoot2.build(),
|
||||||
|
spindexUnjam(spinUnjamTime)
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -630,7 +684,9 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new ParallelAction(
|
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 Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
public static double rx1 = 40, ry1 = -7, rh1 = 0;
|
||||||
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
||||||
public static double rx2b = 31, ry2b = 32, rh2b = 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 rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
|
||||||
public static double rx3b = 34, ry3b = 58, rh3b = 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 rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||||
public static double rx4b = 79, ry4b = 79, rh4b = 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 bx1 = 40, by1 = 7, bh1 = 0;
|
||||||
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140);
|
||||||
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140);
|
||||||
public static double bx2c = 40, by2c = -50, bh2c = 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 bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||||
public static double bx3b = 34, by3b = -58, bh3b = 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 bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||||
public static double bx4b = 75, by4b = -79, bh4b = Math.toRadians(-140);
|
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
|
|||||||
@@ -11,10 +11,10 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.66;
|
public static double spindexer_intakePos3 = 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_outtakeBall2 = 0.31;
|
||||||
public static double spindexer_outtakeBall1 = 0.58;
|
public static double spindexer_outtakeBall1 = 0.15;
|
||||||
|
|
||||||
public static double transferServo_out = 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 hoodDefault = 0.6;
|
||||||
|
|
||||||
public static double hoodAuto = 0.55;
|
public static double hoodAuto = 0.27;
|
||||||
|
|
||||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
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
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
|
||||||
// VELOCITY CONSTANTS
|
// VELOCITY CONSTANTS
|
||||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
||||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||||
}
|
}
|
||||||
@@ -21,6 +21,7 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|||||||
import com.acmerobotics.roadrunner.Vector2d;
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.lynx.LynxModule;
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
@@ -45,10 +46,10 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
public static double shootStamp2 = 0.0;
|
public static double shootStamp2 = 0.0;
|
||||||
public static double spinningPow = 0.2;
|
public static double spinningPow = 0.2;
|
||||||
public static double spindexPos = spindexer_intakePos1;
|
public static double spindexPos = spindexer_intakePos1;
|
||||||
public static double spinPow = 0.08;
|
public static double spinPow = 0.09;
|
||||||
public static double bMult = -1, bDiv = 130000;
|
public static double bMult = 1, bDiv = 2200;
|
||||||
public static double tp = 0.8, ti = 0.001, td = 0.0315, tf = 0;
|
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 double vel = 3000;
|
||||||
public boolean autoVel = true;
|
public boolean autoVel = true;
|
||||||
public double manualOffset = 0.0;
|
public double manualOffset = 0.0;
|
||||||
@@ -146,8 +147,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
tController.setTolerance(0.001);
|
tController.setTolerance(0.001);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
robot.limelight.pipelineSwitch(3);
|
robot.limelight.pipelineSwitch(3);
|
||||||
} else {
|
} else {
|
||||||
@@ -234,31 +233,24 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
intakeTicker++;
|
intakeTicker++;
|
||||||
|
|
||||||
if (intakeTicker % 4 == 0) {
|
if (intakeTicker % 20 < 2) {
|
||||||
spinCurrentPos = servo.getSpinPos();
|
|
||||||
if (Math.abs(spinCurrentPos - spinInitPos) < 0.02) {
|
|
||||||
reverse = true;
|
|
||||||
} else {
|
|
||||||
reverse = false;
|
|
||||||
}
|
|
||||||
spinInitPos = spinCurrentPos;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (intakeTicker % 12 < 3) {
|
|
||||||
|
|
||||||
robot.spin1.setPower(-1);
|
robot.spin1.setPower(-1);
|
||||||
robot.spin2.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.spin1.setPower(1);
|
||||||
robot.spin2.setPower(-1);
|
robot.spin2.setPower(-1);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPower(-spinningPow);
|
robot.spin1.setPower(0.5);
|
||||||
robot.spin2.setPower(spinningPow);
|
robot.spin2.setPower(-0.5);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
intakeStamp = getRuntime();
|
intakeStamp = getRuntime();
|
||||||
TELE.addData("Reverse?", reverse);
|
TELE.addData("Reverse?", reverse);
|
||||||
@@ -386,7 +378,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
||||||
|
|
||||||
desiredTurretAngle += manualOffset;
|
desiredTurretAngle += manualOffset + error;
|
||||||
|
|
||||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||||
|
|
||||||
@@ -406,7 +398,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
pos = 0.83;
|
pos = 0.83;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//SHOOTER:
|
//SHOOTER:
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
@@ -440,58 +431,47 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//TODO: test the camera teleop code
|
//TODO: test the camera teleop code
|
||||||
|
|
||||||
|
|
||||||
TELE.addData("posS2", pos);
|
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
|
if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
|
||||||
// double bearing;
|
double bearing;
|
||||||
//
|
|
||||||
// LLResult result = robot.limelight.getLatestResult();
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
// if (result != null) {
|
if (result != null) {
|
||||||
// if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
// bearing = result.getTx() * bMult;
|
bearing = result.getTx() * bMult;
|
||||||
// overrideTurr = true;
|
|
||||||
//
|
double bearingCorrection = bearing / bDiv;
|
||||||
// double bearingCorrection = bearing / bDiv;
|
|
||||||
//
|
error += bearingCorrection;
|
||||||
// // deadband: ignore tiny noise
|
|
||||||
// if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
camTicker++;
|
||||||
//
|
TELE.addData("tx", bearingCorrection);
|
||||||
// error += bearingCorrection;
|
TELE.addData("ty", result.getTy());
|
||||||
//
|
}
|
||||||
// }
|
}
|
||||||
// camTicker++;
|
|
||||||
// TELE.addData("tx", bearing);
|
} else {
|
||||||
// TELE.addData("ty", result.getTy());
|
camTicker = 0;
|
||||||
// }
|
overrideTurr = false;
|
||||||
// }
|
}
|
||||||
//
|
|
||||||
// } else {
|
|
||||||
// camTicker = 0;
|
|
||||||
// overrideTurr = false;
|
|
||||||
// }
|
|
||||||
|
|
||||||
if (!overrideTurr) {
|
if (!overrideTurr) {
|
||||||
turretPos = pos;
|
turretPos = pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
TELE.addData("posS3", turretPos);
|
TELE.addData("posS3", turretPos);
|
||||||
|
|
||||||
if (manualTurret) {
|
if (manualTurret) {
|
||||||
pos = turrDefault + (manualOffset / 100);
|
pos = turrDefault + (manualOffset / 100) + error;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!overrideTurr) {
|
if (!overrideTurr) {
|
||||||
turretPos = pos;
|
turretPos = pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad2.dpad_right || gamepad1.dpad_right) {
|
if (Math.abs(gamepad2.left_stick_x)>0.2) {
|
||||||
manualOffset -= 2;
|
manualOffset += 1.35 * gamepad2.left_stick_x;
|
||||||
} else if (gamepad2.dpad_left || gamepad1.dpad_left) {
|
|
||||||
manualOffset += 2;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.turr1.setPosition(pos);
|
robot.turr1.setPosition(pos);
|
||||||
@@ -500,7 +480,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
//HOOD:
|
//HOOD:
|
||||||
|
|
||||||
if (autoHood) {
|
if (autoHood) {
|
||||||
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
robot.hood.setPosition(0.15 + hoodOffset);
|
||||||
} else {
|
} else {
|
||||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||||
}
|
}
|
||||||
@@ -518,7 +498,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
if (gamepad2.cross) {
|
if (gamepad2.cross) {
|
||||||
manualOffset = 0;
|
manualOffset = 0;
|
||||||
fixedTurret = true;
|
overrideTurr = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad2.squareWasPressed()) {
|
if (gamepad2.squareWasPressed()) {
|
||||||
@@ -552,21 +532,40 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// }
|
// }
|
||||||
// }
|
// }
|
||||||
|
|
||||||
if (gamepad1.leftBumperWasPressed()) {
|
if (gamepad1.left_bumper) {
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
autoSpintake = false;
|
autoSpintake = false;
|
||||||
|
|
||||||
|
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.spin1.setPower(1);
|
||||||
robot.spin2.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()) {
|
||||||
shootStamp = getRuntime();
|
shootStamp = getRuntime();
|
||||||
shootAll = true;
|
shootAll = true;
|
||||||
spindexPos = spindexer_intakePos1;
|
|
||||||
|
|
||||||
shooterTicker = 0;
|
shooterTicker = 0;
|
||||||
}
|
}
|
||||||
@@ -603,6 +602,70 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
//
|
||||||
|
// 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()) {
|
// if (gamepad1.squareWasPressed()) {
|
||||||
// square = true;
|
// square = true;
|
||||||
// shootStamp = getRuntime();
|
// shootStamp = getRuntime();
|
||||||
|
|||||||
@@ -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
|
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
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());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
limelight.pipelineSwitch(pipeline);
|
limelight.pipelineSwitch(pipeline);
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|||||||
Reference in New Issue
Block a user