Compare commits
4 Commits
LimelightP
...
486bde729d
| Author | SHA1 | Date | |
|---|---|---|---|
| 486bde729d | |||
| 80f095cd57 | |||
| 0549902505 | |||
| cfb51cfa15 |
@@ -133,8 +133,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
robot.spin1.setPosition(spinPID);
|
||||
robot.spin2.setPosition(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
@@ -143,8 +143,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (servo.spinEqual(spindexer)){
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
@@ -224,8 +224,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
||||
|
||||
if (!servo.spinEqual(position)){
|
||||
double spinPID = servo.setSpinPos(position);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
robot.spin1.setPosition(spinPID);
|
||||
robot.spin2.setPosition(-spinPID);
|
||||
}
|
||||
|
||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||
@@ -259,8 +259,8 @@ public class AutoClose_V3 extends LinearOpMode {
|
||||
|
||||
robot.intake.setPower(1);
|
||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
if (getRuntime() - stamp - intakeTime < 1){
|
||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||
return true;
|
||||
|
||||
@@ -31,8 +31,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||
|
||||
public class AutoFar_V1 extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
@@ -133,8 +132,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
||||
robot.shooter2.setPower(powPID);
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
robot.spin1.setPosition(spinPID);
|
||||
robot.spin2.setPosition(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
@@ -143,8 +142,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (servo.spinEqual(spindexer)){
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
@@ -224,8 +223,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
||||
|
||||
if (!servo.spinEqual(position)){
|
||||
double spinPID = servo.setSpinPos(position);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
robot.spin1.setPosition(spinPID);
|
||||
robot.spin2.setPosition(-spinPID);
|
||||
}
|
||||
|
||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||
@@ -259,8 +258,8 @@ public class AutoFar_V1 extends LinearOpMode {
|
||||
|
||||
robot.intake.setPower(1);
|
||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
if (getRuntime() - stamp - intakeTime < 1){
|
||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||
return true;
|
||||
|
||||
@@ -0,0 +1,539 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2a;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2c;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.ParallelAction;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||
@Config
|
||||
public class Auto_LT extends LinearOpMode {
|
||||
|
||||
public int motif = 0;
|
||||
|
||||
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
|
||||
public static double autoSpinStartPos = 0.2;
|
||||
public static double shoot0SpinSpeedIncrease = 0.014;
|
||||
public static double obeliskTurrPos = 0.53;
|
||||
|
||||
public static double shoot1Turr = 0.57;
|
||||
|
||||
public static double shoot0XTolerance = 1.0;
|
||||
public static double shoot0Time = 1.8;
|
||||
|
||||
public static double intake1Time = 5.0;
|
||||
|
||||
public static double flywheel0Time = 3.5;
|
||||
public static double pickup1Speed = 20.0;
|
||||
|
||||
// ---- SECOND SHOT / PICKUP ----
|
||||
public static double shoot1Vel = 2300;
|
||||
public static double shoot1Hood = 0.93;
|
||||
|
||||
// ---- PICKUP TIMING ----
|
||||
public static double pickup1Time = 3.0;
|
||||
|
||||
// ---- PICKUP POSITION TOLERANCES ----
|
||||
public static double pickup1XTolerance = 2.0;
|
||||
public static double pickup1YTolerance = 2.0;
|
||||
|
||||
// ---- OBELISK DETECTION ----
|
||||
public static double obelisk1Time = 1.5;
|
||||
public static double obelisk1XTolerance = 2.0;
|
||||
public static double obelisk1YTolerance = 2.0;
|
||||
|
||||
public static double shoot1ToleranceX = 2.0;
|
||||
public static double shoot1ToleranceY = 2.0;
|
||||
public static double shoot1Time = 2.0;
|
||||
|
||||
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
Servos servos;
|
||||
Spindexer spindexer;
|
||||
Flywheel flywheel;
|
||||
Turret turret;
|
||||
private double x1, y1, h1;
|
||||
|
||||
private double x2a, y2a, h2a, t2a;
|
||||
|
||||
private double x2b, y2b, h2b, t2b;
|
||||
private double x2c, y2c, h2c, t2c;
|
||||
|
||||
private double xShoot, yShoot, hShoot;
|
||||
|
||||
public Action prepareShootAll(double time) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
robot.turr1.setPosition(shoot1Turr);
|
||||
robot.turr1.setPosition(1-shoot1Turr);
|
||||
|
||||
|
||||
robot.spin1.setPosition(autoSpinStartPos);
|
||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.intake.setPower(-((System.currentTimeMillis() - stamp))/1000);
|
||||
|
||||
return (System.currentTimeMillis() - stamp) < (time * 1000);
|
||||
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAll(int vel, double shootTime) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
|
||||
double stamp = 0.0;
|
||||
|
||||
double velo = vel;
|
||||
|
||||
int shooterTicker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("shooting");
|
||||
TELE.update();
|
||||
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
robot.intake.setPower(-0.3);
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = getRuntime();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
robot.intake.setPower(0);
|
||||
|
||||
if (getRuntime() - stamp < shootTime) {
|
||||
|
||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
||||
robot.spin1.setPosition(autoSpinStartPos);
|
||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
shooterTicker++;
|
||||
double prevSpinPos = robot.spin1.getPosition();
|
||||
robot.spin1.setPosition(prevSpinPos + shoot0SpinSpeedIncrease);
|
||||
robot.spin2.setPosition(1 - prevSpinPos - shoot0SpinSpeedIncrease);
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
return false;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
spindexer.processIntake();
|
||||
robot.intake.setPower(1);
|
||||
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
return (System.currentTimeMillis() - stamp) < (intakeTime * 1000);
|
||||
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
public Action detectObelisk(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance,
|
||||
double turrPos
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
robot.turr1.setPosition(turrPos);
|
||||
robot.turr2.setPosition(1 - turrPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
|
||||
return !shouldFinish;
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageFlywheel(
|
||||
double vel,
|
||||
double hoodPos,
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
flywheel.manageFlywheel(vel);
|
||||
robot.hood.setPosition(hoodPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
|
||||
return !shouldFinish;
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
hardwareMap.get(Servo.class, "light").setPosition(0);
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
Targeting targeting = new Targeting();
|
||||
Targeting.Settings targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
servos = new Servos(hardwareMap);
|
||||
|
||||
robot.limelight.pipelineSwitch(1);
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight);
|
||||
|
||||
turret.manualSetTurret(0.4);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||
|
||||
TrajectoryActionBuilder shoot0;
|
||||
|
||||
TrajectoryActionBuilder pickup1;
|
||||
TrajectoryActionBuilder shoot1;
|
||||
|
||||
robot.spin1.setPosition(autoSpinStartPos);
|
||||
robot.spin2.setPosition(1 - autoSpinStartPos);
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
robot.light.setPosition(1);
|
||||
|
||||
while (opModeInInit()) {
|
||||
|
||||
robot.hood.setPosition(shoot0Hood);
|
||||
|
||||
if (gamepad2.crossWasPressed()) {
|
||||
redAlliance = !redAlliance;
|
||||
}
|
||||
|
||||
if (redAlliance) {
|
||||
robot.light.setPosition(0.28);
|
||||
|
||||
// ---- FIRST SHOT ----
|
||||
x1 = rx1;
|
||||
y1 = ry1;
|
||||
h1 = rh1;
|
||||
|
||||
// ---- PICKUP PATH ----
|
||||
x2a = rx2a;
|
||||
y2a = ry2a;
|
||||
h2a = rh2a;
|
||||
t2a = rt2a;
|
||||
x2b = rx2b;
|
||||
y2b = ry2b;
|
||||
h2b = rh2b;
|
||||
t2b = rt2b;
|
||||
x2c = rx2c;
|
||||
y2c = ry2c;
|
||||
h2c = rh2c;
|
||||
t2c = rt2c;
|
||||
|
||||
xShoot = rShootX;
|
||||
yShoot = rShootY;
|
||||
hShoot = rShootH;
|
||||
|
||||
} else {
|
||||
robot.light.setPosition(0.6);
|
||||
|
||||
// ---- FIRST SHOT ----
|
||||
x1 = bx1;
|
||||
y1 = by1;
|
||||
h1 = bh1;
|
||||
|
||||
// ---- PICKUP PATH ----
|
||||
x2a = bx2a;
|
||||
y2a = by2a;
|
||||
h2a = bh2a;
|
||||
t2a = bt2a;
|
||||
x2b = bx2b;
|
||||
y2b = by2b;
|
||||
h2b = bh2b;
|
||||
t2b = bt2b;
|
||||
x2c = bx2c;
|
||||
y2c = by2c;
|
||||
h2c = bh2c;
|
||||
t2c = bt2c;
|
||||
|
||||
xShoot = bShootX;
|
||||
yShoot = bShootY;
|
||||
hShoot = bShootH;
|
||||
}
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
||||
|
||||
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
|
||||
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
|
||||
new TranslationalVelConstraint(pickup1Speed));
|
||||
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
|
||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
||||
|
||||
|
||||
}
|
||||
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
|
||||
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
|
||||
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
|
||||
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
|
||||
new TranslationalVelConstraint(pickup1Speed));
|
||||
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
|
||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()) {
|
||||
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
manageFlywheel(
|
||||
shoot0Vel,
|
||||
shoot0Hood,
|
||||
flywheel0Time,
|
||||
x1,
|
||||
0.501,
|
||||
shoot0XTolerance,
|
||||
0.501
|
||||
)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
Actions.runBlocking(
|
||||
shootAll((int) shoot0Vel, shoot0Time)
|
||||
);
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
pickup1.build(),
|
||||
manageFlywheel(
|
||||
shoot1Vel,
|
||||
shoot1Hood,
|
||||
pickup1Time,
|
||||
x2b,
|
||||
y2b,
|
||||
pickup1XTolerance,
|
||||
pickup1YTolerance
|
||||
),
|
||||
intake(intake1Time),
|
||||
detectObelisk(
|
||||
obelisk1Time,
|
||||
x2b,
|
||||
y2c,
|
||||
obelisk1XTolerance,
|
||||
obelisk1YTolerance,
|
||||
obeliskTurrPos
|
||||
)
|
||||
)
|
||||
);
|
||||
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
manageFlywheel(
|
||||
shoot1Vel,
|
||||
shoot1Hood,
|
||||
shoot1Time,
|
||||
xShoot,
|
||||
yShoot,
|
||||
shoot1ToleranceX,
|
||||
shoot1ToleranceY
|
||||
),
|
||||
shoot1.build(),
|
||||
prepareShootAll(shoot1Time)
|
||||
)
|
||||
);
|
||||
|
||||
Actions.runBlocking(
|
||||
shootAll((int) shoot1Vel, shoot0Time)
|
||||
);
|
||||
|
||||
|
||||
|
||||
|
||||
TELE.addData("ID", motif);
|
||||
|
||||
TELE.update();
|
||||
|
||||
robot.intake.setPower(0);
|
||||
|
||||
sleep(5000);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -182,8 +182,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
spinPID = servo.setSpinPos(spindexer);
|
||||
robot.spin1.setPower(spinPID);
|
||||
robot.spin2.setPower(-spinPID);
|
||||
robot.spin1.setPosition(spinPID);
|
||||
robot.spin2.setPosition(-spinPID);
|
||||
TELE.addData("Velocity", velo);
|
||||
TELE.addLine("spindex");
|
||||
TELE.update();
|
||||
@@ -192,8 +192,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
if (servo.spinEqual(spindexer)) {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
|
||||
return false;
|
||||
} else {
|
||||
@@ -203,6 +203,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
public Action Shoot(int vel) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
@@ -240,8 +241,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
robot.spin1.setPosition(-spinPow);
|
||||
robot.spin2.setPosition(spinPow);
|
||||
return true;
|
||||
|
||||
} else {
|
||||
@@ -271,12 +272,12 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
if (ticker % 12 < 6) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
robot.spin1.setPosition(-1);
|
||||
robot.spin2.setPosition(1);
|
||||
|
||||
} else {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
robot.spin1.setPosition(1);
|
||||
robot.spin2.setPosition(-1);
|
||||
}
|
||||
|
||||
if (getRuntime() - stamp > jamTime+0.4) {
|
||||
@@ -317,20 +318,20 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
if (ticker % 60 < 12) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
robot.spin1.setPosition(-1);
|
||||
robot.spin2.setPosition(1);
|
||||
|
||||
} else if (ticker % 60 < 30) {
|
||||
robot.spin1.setPower(-0.5);
|
||||
robot.spin2.setPower(0.5);
|
||||
robot.spin1.setPosition(-0.5);
|
||||
robot.spin2.setPosition(0.5);
|
||||
}
|
||||
else if (ticker % 60 < 42) {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
robot.spin1.setPosition(1);
|
||||
robot.spin2.setPosition(-1);
|
||||
}
|
||||
else {
|
||||
robot.spin1.setPower(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
robot.spin1.setPosition(0.5);
|
||||
robot.spin2.setPosition(-0.5);
|
||||
}
|
||||
robot.intake.setPower(1);
|
||||
TELE.addData("Reverse?", reverse);
|
||||
@@ -338,11 +339,11 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
|
||||
if (getRuntime() - stamp > intakeTime) {
|
||||
if (reverse) {
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
robot.spin1.setPosition(-1);
|
||||
robot.spin2.setPosition(1);
|
||||
} else {
|
||||
robot.spin1.setPower(1);
|
||||
robot.spin2.setPower(-1);
|
||||
robot.spin1.setPosition(1);
|
||||
robot.spin2.setPosition(-1);
|
||||
}
|
||||
return false;
|
||||
} else {
|
||||
|
||||
@@ -2,4 +2,5 @@ package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class Color {
|
||||
public static boolean redAlliance = true;
|
||||
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,47 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
|
||||
@Config
|
||||
public class Poses_V2 {
|
||||
|
||||
public static double goalHeight = 42; //in inches
|
||||
|
||||
public static double turretHeight = 12;
|
||||
|
||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||
|
||||
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
|
||||
|
||||
public static double rx1 = 20, ry1 = 0, rh1 = 0;
|
||||
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI/2);
|
||||
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI/2);
|
||||
|
||||
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI/2);
|
||||
|
||||
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 = 72, ry4a = 55, rh4a = Math.toRadians(140);
|
||||
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
|
||||
|
||||
public static double bx1 = 20, by1 = 0, bh1 = 0;
|
||||
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
|
||||
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
|
||||
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
|
||||
|
||||
public static double rShootX = 40, rShootY = 30, rShootH = Math.toRadians(140);
|
||||
|
||||
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
|
||||
|
||||
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
|
||||
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
|
||||
|
||||
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
|
||||
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||
|
||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
||||
|
||||
}
|
||||
@@ -5,16 +5,18 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
public class ServoPositions {
|
||||
|
||||
public static double spindexer_intakePos1 = 0.18;
|
||||
public static double spindexer_intakePos1 = 0.13;
|
||||
|
||||
public static double spindexer_intakePos2 = 0.36;//0.5;
|
||||
public static double spindexer_intakePos2 = 0.33;//0.5;
|
||||
|
||||
public static double spindexer_intakePos3 = 0.54;//0.66;
|
||||
public static double spindexer_intakePos3 = 0.53;//0.66;
|
||||
|
||||
public static double spindexer_outtakeBall3 = 0.47;
|
||||
public static double spindexer_outtakeBall3 = 0.8;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.6;
|
||||
public static double spindexer_outtakeBall1 = 0.4;
|
||||
public static double spinStartPos = spindexer_outtakeBall1 - 0.08;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.31;
|
||||
public static double spindexer_outtakeBall1 = 0.15;
|
||||
|
||||
public static double transferServo_out = 0.15;
|
||||
|
||||
|
||||
@@ -162,11 +162,11 @@ public class TeleopV2 extends LinearOpMode {
|
||||
//TODO: make sure changing position works throughout opmode
|
||||
if (!servo.spinEqual(spindexPos)){
|
||||
spindexPID = servo.setSpinPos(spindexPos);
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
robot.spin1.setPosition(spindexPID);
|
||||
robot.spin2.setPosition(-spindexPID);
|
||||
} else{
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
}
|
||||
|
||||
//INTAKE:
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
package org.firstinspires.ftc.teamcode.teleop;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
@@ -121,6 +122,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
private int tickerA = 1;
|
||||
private boolean transferIn = false;
|
||||
boolean turretInterpolate = false;
|
||||
public static double spinSpeedIncrease = 0.04;
|
||||
|
||||
public static double velPrediction(double distance) {
|
||||
if (distance < 30) {
|
||||
@@ -139,13 +141,15 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
robot.light.setPosition(0);
|
||||
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||
|
||||
for (LynxModule hub : allHubs) {
|
||||
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||
}
|
||||
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
servo = new Servos(hardwareMap);
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
@@ -167,14 +171,16 @@ public class TeleopV3 extends LinearOpMode {
|
||||
// robot.limelight.start();
|
||||
|
||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||
waitForStart();
|
||||
|
||||
robot.light.setPosition(1);
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
while (opModeIsActive()) {
|
||||
// LIGHT COLORS
|
||||
spindexer.ballCounterLight();
|
||||
|
||||
//DRIVETRAIN:
|
||||
|
||||
double y = 0.0;
|
||||
@@ -233,37 +239,43 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//TODO: Use color sensors to switch between positions...switch after ball detected in
|
||||
|
||||
if (gamepad1.right_bumper){
|
||||
shootAll = false;
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
}
|
||||
|
||||
if (autoSpintake) {
|
||||
|
||||
if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) {
|
||||
spinCurrentPos = servo.getSpinPos();
|
||||
|
||||
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos);
|
||||
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
robot.spin1.setPosition(spindexPos);
|
||||
robot.spin2.setPosition(1-spindexPos);
|
||||
|
||||
}
|
||||
|
||||
if (gamepad1.right_bumper) {
|
||||
|
||||
shootAll = false;
|
||||
|
||||
intakeTicker++;
|
||||
|
||||
if (intakeTicker % 20 < 2) {
|
||||
|
||||
robot.spin1.setPower(-1);
|
||||
robot.spin2.setPower(1);
|
||||
|
||||
} 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(0.5);
|
||||
robot.spin2.setPower(-0.5);
|
||||
}
|
||||
// if (intakeTicker % 20 < 2) {
|
||||
//
|
||||
// robot.spin1.setPower(-1);
|
||||
// robot.spin2.setPower(1);
|
||||
//
|
||||
// } 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(0.5);
|
||||
// robot.spin2.setPower(-0.5);
|
||||
// }
|
||||
|
||||
robot.intake.setPower(1);
|
||||
intakeStamp = getRuntime();
|
||||
@@ -271,17 +283,9 @@ public class TeleopV3 extends LinearOpMode {
|
||||
TELE.update();
|
||||
} else {
|
||||
if (!servo.spinEqual(spindexPos)) {
|
||||
spinCurrentPos = servo.getSpinPos();
|
||||
robot.spin1.setPosition(spindexPos);
|
||||
robot.spin2.setPosition(1-spindexPos);
|
||||
|
||||
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos);
|
||||
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
|
||||
} else {
|
||||
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
}
|
||||
|
||||
spindexPos = spindexer_intakePos1;
|
||||
@@ -506,76 +510,76 @@ public class TeleopV3 extends LinearOpMode {
|
||||
// }
|
||||
// }
|
||||
|
||||
if (gamepad1.left_bumper && !enableSpindexerManager) {
|
||||
//if (gamepad1.left_bumper && !enableSpindexerManager) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
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.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() && !enableSpindexerManager) {
|
||||
shootStamp = getRuntime();
|
||||
shootAll = true;
|
||||
|
||||
shooterTicker = 0;
|
||||
}
|
||||
|
||||
if (shootAll && !enableSpindexerManager) {
|
||||
|
||||
TELE.addData("100% works", shootOrder);
|
||||
|
||||
intake = false;
|
||||
reject = false;
|
||||
|
||||
shooterTicker++;
|
||||
|
||||
spindexPos = spindexer_intakePos1;
|
||||
|
||||
if (getRuntime() - shootStamp < 3.5) {
|
||||
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
autoSpintake = false;
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
spindexPos = spindexer_intakePos1;
|
||||
|
||||
shootAll = false;
|
||||
|
||||
autoSpintake = true;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
}
|
||||
|
||||
}
|
||||
// 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.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() && !enableSpindexerManager) {
|
||||
// shootStamp = getRuntime();
|
||||
// shootAll = true;
|
||||
//
|
||||
// shooterTicker = 0;
|
||||
// }
|
||||
//
|
||||
// if (shootAll && !enableSpindexerManager) {
|
||||
//
|
||||
// TELE.addData("100% works", shootOrder);
|
||||
//
|
||||
// intake = false;
|
||||
// reject = false;
|
||||
//
|
||||
// shooterTicker++;
|
||||
//
|
||||
// spindexPos = spindexer_intakePos1;
|
||||
//
|
||||
// if (getRuntime() - shootStamp < 3.5) {
|
||||
//
|
||||
// robot.transferServo.setPosition(transferServo_in);
|
||||
//
|
||||
// autoSpintake = false;
|
||||
//
|
||||
// robot.spin1.setPower(-spinPow);
|
||||
// robot.spin2.setPower(spinPow);
|
||||
//
|
||||
// } else {
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
// spindexPos = spindexer_intakePos1;
|
||||
//
|
||||
// shootAll = false;
|
||||
//
|
||||
// autoSpintake = true;
|
||||
//
|
||||
// robot.transferServo.setPosition(transferServo_out);
|
||||
// }
|
||||
//
|
||||
// }
|
||||
|
||||
if (enableSpindexerManager) {
|
||||
if (!shootAll) {
|
||||
@@ -599,6 +603,8 @@ public class TeleopV3 extends LinearOpMode {
|
||||
shootAll = true;
|
||||
|
||||
shooterTicker = 0;
|
||||
spindexPos = spinStartPos;// TODO: Change starting position based on desired order to shoot green ball
|
||||
|
||||
}
|
||||
|
||||
if (shootAll) {
|
||||
@@ -606,17 +612,18 @@ public class TeleopV3 extends LinearOpMode {
|
||||
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) {
|
||||
|
||||
if (shooterTicker == 0 && !servo.spinEqual(spindexPos)){
|
||||
robot.spin1.setPosition(spindexPos);
|
||||
robot.spin2.setPosition(1-spindexPos);
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
shooterTicker++;
|
||||
double prevSpinPos = robot.spin1.getPosition();
|
||||
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
|
||||
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
|
||||
}
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
@@ -624,12 +631,19 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
shootAll = false;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
}
|
||||
}
|
||||
|
||||
if (gamepad1.left_stick_button){
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
shootAll = false;
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
|
||||
@@ -16,8 +16,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
|
||||
public class IntakeTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
@@ -72,19 +71,19 @@ public class IntakeTest extends LinearOpMode {
|
||||
initPos = currentPos;
|
||||
}
|
||||
if (reverse){
|
||||
robot.spin1.setPower(manualPow);
|
||||
robot.spin2.setPower(-manualPow);
|
||||
robot.spin1.setPosition(manualPow);
|
||||
robot.spin2.setPosition(-manualPow);
|
||||
} else {
|
||||
robot.spin1.setPower(-manualPow);
|
||||
robot.spin2.setPower(manualPow);
|
||||
robot.spin1.setPosition(-manualPow);
|
||||
robot.spin2.setPosition(manualPow);
|
||||
}
|
||||
robot.intake.setPower(1);
|
||||
stamp = getRuntime();
|
||||
TELE.addData("Reverse?", reverse);
|
||||
TELE.update();
|
||||
} else {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
|
||||
if (getRuntime() - stamp < 1) {
|
||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||
@@ -191,15 +190,15 @@ public class IntakeTest extends LinearOpMode {
|
||||
|
||||
if (!atTarget) {
|
||||
powPID = servo.setSpinPos(spindexerPos);
|
||||
robot.spin1.setPower(powPID);
|
||||
robot.spin2.setPower(-powPID);
|
||||
robot.spin1.setPosition(powPID);
|
||||
robot.spin2.setPosition(-powPID);
|
||||
|
||||
steadySpin = false;
|
||||
wasMoving = true; // remember we were moving
|
||||
stamp = getRuntime();
|
||||
} else {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
robot.spin1.setPosition(0);
|
||||
robot.spin2.setPosition(0);
|
||||
steadySpin = true;
|
||||
wasMoving = false;
|
||||
}
|
||||
|
||||
@@ -17,7 +17,7 @@ public class LimelightTest extends LinearOpMode {
|
||||
MultipleTelemetry TELE;
|
||||
Turret turret;
|
||||
Robot robot;
|
||||
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
||||
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 4 is for red track; DO NOT USE 3
|
||||
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||
public static boolean turretMode = false;
|
||||
public static double turretPos = 0.501;
|
||||
|
||||
@@ -9,8 +9,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class PIDServoTest extends LinearOpMode {
|
||||
|
||||
public static double p = 2, i = 0, d = 0, f = 0;
|
||||
@@ -47,8 +45,8 @@ public class PIDServoTest extends LinearOpMode {
|
||||
|
||||
double pid = controller.calculate(pos, target);
|
||||
|
||||
robot.spin1.setPower(pid);
|
||||
robot.spin2.setPower(-pid);
|
||||
robot.spin1.setPosition(pid);
|
||||
robot.spin2.setPosition(-pid);
|
||||
}
|
||||
|
||||
telemetry.addData("pos", pos);
|
||||
|
||||
@@ -1,8 +1,11 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinSpeedIncrease;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@@ -13,6 +16,7 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
|
||||
@Config
|
||||
@@ -36,6 +40,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
public static boolean intake = false;
|
||||
Robot robot;
|
||||
Flywheel flywheel;
|
||||
Servos servo;
|
||||
|
||||
double shootStamp = 0.0;
|
||||
boolean shootAll = false;
|
||||
@@ -45,6 +50,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
public static boolean enableHoodAutoOpen = false;
|
||||
public double hoodAdjust = 0.0;
|
||||
public static double hoodAdjustFactor = 1.0;
|
||||
private int shooterTicker = 0;
|
||||
Spindexer spindexer ;
|
||||
|
||||
@Override
|
||||
@@ -55,6 +61,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
DcMotorEx rightShooter = robot.shooter2;
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
servo = new Servos(hardwareMap);
|
||||
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -95,6 +102,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
shootAll = true;
|
||||
shoot = false;
|
||||
robot.transfer.setPower(transferPower);
|
||||
shooterTicker = 0;
|
||||
}
|
||||
if (shootAll) {
|
||||
|
||||
@@ -103,24 +111,31 @@ public class ShooterTest extends LinearOpMode {
|
||||
|
||||
// TODO: Change starting position based on desired order to shoot green ball
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
if (getRuntime() - shootStamp < 3.5) {
|
||||
|
||||
if (shooterTicker == 0 && !servo.spinEqual(spinStartPos)){
|
||||
robot.spin1.setPosition(spinStartPos);
|
||||
robot.spin2.setPosition(1-spinStartPos);
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_in);
|
||||
shooterTicker++;
|
||||
double prevSpinPos = robot.spin1.getPosition();
|
||||
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
|
||||
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
|
||||
}
|
||||
|
||||
|
||||
robot.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
|
||||
} else {
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
//spindexPos = spindexer_intakePos1;
|
||||
|
||||
shootAll = false;
|
||||
shooterTicker = 0;
|
||||
|
||||
robot.transferServo.setPosition(transferServo_out);
|
||||
robot.transfer.setPower(0);
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
@@ -18,14 +18,10 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
Servos servo;
|
||||
|
||||
public static double spindexPos = 0.501;
|
||||
public static double spindexPow = 0.0;
|
||||
public static double spinHoldPow = 0.0;
|
||||
public static double turretPos = 0.501;
|
||||
public static double turretPow = 0.0;
|
||||
public static double turrHoldPow = 0.0;
|
||||
public static double transferPos = 0.501;
|
||||
public static double hoodPos = 0.501;
|
||||
public static int mode = 0; //0 for positional, 1 for power
|
||||
public static double light = 0.501;
|
||||
|
||||
Turret turret;
|
||||
|
||||
@@ -35,22 +31,13 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
servo = new Servos(hardwareMap);
|
||||
|
||||
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight );
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
while (opModeIsActive()){
|
||||
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos) && mode == 0){
|
||||
double pos = servo.setSpinPos(spindexPos);
|
||||
robot.spin1.setPower(pos);
|
||||
robot.spin2.setPower(-pos);
|
||||
} else if (mode == 0){
|
||||
robot.spin1.setPower(spinHoldPow);
|
||||
robot.spin2.setPower(spinHoldPow);
|
||||
} else {
|
||||
robot.spin1.setPower(spindexPow);
|
||||
robot.spin2.setPower(-spindexPow);
|
||||
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos)){
|
||||
robot.spin1.setPosition(spindexPos);
|
||||
robot.spin2.setPosition(1-spindexPos);
|
||||
}
|
||||
if (turretPos != 0.501){
|
||||
robot.turr1.setPosition(turretPos);
|
||||
@@ -62,6 +49,9 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
if (hoodPos != 0.501){
|
||||
robot.hood.setPosition(hoodPos);
|
||||
}
|
||||
if (light !=0.501){
|
||||
robot.light.setPosition(light);
|
||||
}
|
||||
// To check configuration of spindexer:
|
||||
// Set "mode" to 1 and spindexPow to 0.1
|
||||
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
|
||||
@@ -79,7 +69,6 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||
TELE.addData("hood pos", robot.hood.getPosition());
|
||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||
TELE.addData("tpos ", turret.getTurrPos() );
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.arcrobotics.ftclib.hardware.ServoEx;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||
@@ -40,8 +41,10 @@ public class Robot {
|
||||
public Servo transferServo;
|
||||
public Servo turr1;
|
||||
public Servo turr2;
|
||||
public CRServo spin1;
|
||||
public CRServo spin2;
|
||||
|
||||
public Servo spin1;
|
||||
|
||||
public Servo spin2;
|
||||
public AnalogInput spin1Pos;
|
||||
public AnalogInput spin2Pos;
|
||||
public AnalogInput turr1Pos;
|
||||
@@ -52,6 +55,7 @@ public class Robot {
|
||||
public RevColorSensorV3 color2;
|
||||
public RevColorSensorV3 color3;
|
||||
public Limelight3A limelight;
|
||||
public Servo light;
|
||||
|
||||
public Robot(HardwareMap hardwareMap) {
|
||||
|
||||
@@ -93,17 +97,14 @@ public class Robot {
|
||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
||||
|
||||
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
||||
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||
spin1 = hardwareMap.get(Servo.class, "spin2");
|
||||
|
||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||
|
||||
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
||||
spin2 = hardwareMap.get(Servo.class, "spin1");
|
||||
|
||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||
|
||||
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||
|
||||
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
||||
@@ -125,5 +126,7 @@ public class Robot {
|
||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||
}
|
||||
|
||||
light = hardwareMap.get(Servo.class, "light");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -10,8 +10,8 @@ public class Servos {
|
||||
// TODO: get PIDF constants
|
||||
public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||
public static double spin_scalar = 1.0086;
|
||||
public static double spin_restPos = 0.0;
|
||||
public static double spin_scalar = 1.112;
|
||||
public static double spin_restPos = 0.155;
|
||||
public static double turret_scalar = 1.009;
|
||||
public static double turret_restPos = 0.0;
|
||||
Robot robot;
|
||||
@@ -27,16 +27,14 @@ public class Servos {
|
||||
}
|
||||
|
||||
// In the code below, encoder = robot.servo.getVoltage()
|
||||
|
||||
// TODO: set the restPos and scalar
|
||||
public double getSpinPos() {
|
||||
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3);
|
||||
}
|
||||
|
||||
//TODO: PID warp so 0 and 1 are usable positions
|
||||
public double setSpinPos(double pos) {
|
||||
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
||||
|
||||
return spinPID.calculate(this.getSpinPos(), pos);
|
||||
return pos;
|
||||
}
|
||||
|
||||
public boolean spinEqual(double pos) {
|
||||
@@ -45,7 +43,6 @@ public class Servos {
|
||||
|
||||
public double getTurrPos() {
|
||||
return 1.0;
|
||||
|
||||
}
|
||||
|
||||
public double setTurrPos(double pos) {
|
||||
|
||||
@@ -4,6 +4,7 @@ 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.Color.*;
|
||||
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;
|
||||
@@ -67,7 +68,7 @@ public class Spindexer {
|
||||
SHOOTWAIT,
|
||||
SHOOT_ALL_PREP,
|
||||
SHOOT_ALL_READY
|
||||
};
|
||||
}
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
public int unknownColorDetect = 0;
|
||||
@@ -75,7 +76,7 @@ public class Spindexer {
|
||||
UNKNOWN,
|
||||
GREEN,
|
||||
PURPLE
|
||||
};
|
||||
}
|
||||
|
||||
class BallPosition {
|
||||
boolean isEmpty = true;
|
||||
@@ -247,17 +248,34 @@ public class Spindexer {
|
||||
}
|
||||
|
||||
public void moveSpindexerToPos(double pos) {
|
||||
spinCurrentPos = servos.getSpinPos();
|
||||
|
||||
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
||||
|
||||
robot.spin1.setPower(spindexPID);
|
||||
robot.spin2.setPower(-spindexPID);
|
||||
robot.spin1.setPosition(pos);
|
||||
robot.spin2.setPosition(1-pos);
|
||||
}
|
||||
|
||||
public void stopSpindexer() {
|
||||
robot.spin1.setPower(0);
|
||||
robot.spin2.setPower(0);
|
||||
|
||||
}
|
||||
|
||||
public void ballCounterLight(){
|
||||
int counter = 0;
|
||||
if (!ballPositions[0].isEmpty){
|
||||
counter++;
|
||||
}
|
||||
if (!ballPositions[1].isEmpty){
|
||||
counter++;
|
||||
}
|
||||
if (!ballPositions[2].isEmpty){
|
||||
counter++;
|
||||
}
|
||||
if (counter == 3){
|
||||
robot.light.setPosition(Light3);
|
||||
} else if (counter == 2){
|
||||
robot.light.setPosition(Light2);
|
||||
} else if (counter == 1){
|
||||
robot.light.setPosition(Light1);
|
||||
} else {
|
||||
robot.light.setPosition(Light0);
|
||||
}
|
||||
}
|
||||
|
||||
public boolean isFull () {
|
||||
|
||||
@@ -63,7 +63,7 @@ public class Turret {
|
||||
this.webcam = cam;
|
||||
webcam.start();
|
||||
if (redAlliance) {
|
||||
webcam.pipelineSwitch(3);
|
||||
webcam.pipelineSwitch(4);
|
||||
} else {
|
||||
webcam.pipelineSwitch(2);
|
||||
}
|
||||
|
||||
@@ -26,10 +26,10 @@ dependencies {
|
||||
|
||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||
|
||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
||||
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
||||
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash
|
||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
||||
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
||||
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
||||
|
||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||
|
||||
|
||||
Reference in New Issue
Block a user