Compare commits
6 Commits
organize/e
...
d5a3457be2
| Author | SHA1 | Date | |
|---|---|---|---|
| d5a3457be2 | |||
| 554204b6d4 | |||
| d586e3b4df | |||
| 2f5d4638ec | |||
| 1642e161c5 | |||
| 46a565c2c8 |
@@ -1,606 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
import com.acmerobotics.roadrunner.ParallelAction;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.acmerobotics.roadrunner.SequentialAction;
|
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class AutoClose_V3 extends LinearOpMode {
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
FlywheelV2 flywheel;
|
|
||||||
Servos servo;
|
|
||||||
LimelightManager limelightManager;
|
|
||||||
|
|
||||||
double velo = 0.0;
|
|
||||||
public static double intake1Time = 2.7;
|
|
||||||
public static double intake2Time = 3.0;
|
|
||||||
public static double colorDetect = 3.0;
|
|
||||||
public static double holdTurrPow = 0.1;
|
|
||||||
|
|
||||||
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
|
||||||
int b1 = 0, b2 = 0, b3 = 0;
|
|
||||||
boolean gpp = false, pgp = false, ppg = false;
|
|
||||||
double powPID = 0.0;
|
|
||||||
double bearing = 0.0;
|
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !flywheel.getSteady();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action Obelisk() {
|
|
||||||
return new Action() {
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
limelightManager.update();
|
|
||||||
int id = limelightManager.detectFiducial();
|
|
||||||
|
|
||||||
if (id == 21) gpp = true;
|
|
||||||
else if (id == 22) pgp = true;
|
|
||||||
else if (id == 23) ppg = true;
|
|
||||||
|
|
||||||
TELE.addData("Fiducial ID", id);
|
|
||||||
TELE.addData("21", gpp);
|
|
||||||
TELE.addData("22", pgp);
|
|
||||||
TELE.addData("23", ppg);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (gpp || pgp || ppg) {
|
|
||||||
LimelightManager.LimelightMode mode = redAlliance ?
|
|
||||||
LimelightManager.LimelightMode.RED_GOAL :
|
|
||||||
LimelightManager.LimelightMode.BLUE_GOAL;
|
|
||||||
limelightManager.switchMode(mode);
|
|
||||||
|
|
||||||
double turretTarget = redAlliance ? turret_redClose : turret_blueClose;
|
|
||||||
double turretPID = servo.setTurrPos(turretTarget);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
return !servo.turretEqual(turretTarget);
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action spindex(double spindexer, int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double spinPID = 0.0;
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
|
||||||
robot.spin1.setPower(spinPID);
|
|
||||||
robot.spin2.setPower(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action Shoot(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double transferStamp = 0.0;
|
|
||||||
int ticker = 1;
|
|
||||||
boolean transferIn = false;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("shooting");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
detectTag();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
transferStamp = getRuntime();
|
|
||||||
ticker++;
|
|
||||||
}
|
|
||||||
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addData("ticker", ticker);
|
|
||||||
TELE.update();
|
|
||||||
transferIn = true;
|
|
||||||
return true;
|
|
||||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
robot.turr1.setPower(holdTurrPow);
|
|
||||||
robot.turr2.setPower(holdTurrPow);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("shot once");
|
|
||||||
TELE.update();
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
|
||||||
return new Action() {
|
|
||||||
double position = spindexer_intakePos1;
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
double pow = 1.0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.intake.setPower(pow);
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
|
||||||
double spinPID = servo.setSpinPos(position);
|
|
||||||
robot.spin1.setPower(spinPID);
|
|
||||||
robot.spin2.setPower(-spinPID);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
|
||||||
if (s2D > 60){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
position = spindexer_intakePos2;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
position = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
position = spindexer_intakePos1;
|
|
||||||
}
|
|
||||||
} else if (s3D > 33){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
position = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
position = spindexer_intakePos1;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
position = spindexer_intakePos2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("Intaking");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
if (getRuntime() - stamp - intakeTime < 1){
|
|
||||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action ColorDetect(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (s1D < 43) {
|
|
||||||
|
|
||||||
double green = robot.color1.getNormalizedColors().green;
|
|
||||||
double red = robot.color1.getNormalizedColors().red;
|
|
||||||
double blue = robot.color1.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b1 = 2;
|
|
||||||
} else {
|
|
||||||
b1 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s2D < 60) {
|
|
||||||
|
|
||||||
double green = robot.color2.getNormalizedColors().green;
|
|
||||||
double red = robot.color2.getNormalizedColors().red;
|
|
||||||
double blue = robot.color2.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b2 = 2;
|
|
||||||
} else {
|
|
||||||
b2 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s3D < 33) {
|
|
||||||
|
|
||||||
double green = robot.color3.getNormalizedColors().green;
|
|
||||||
double red = robot.color3.getNormalizedColors().red;
|
|
||||||
double blue = robot.color3.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b3 = 2;
|
|
||||||
} else {
|
|
||||||
b3 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("Detecting");
|
|
||||||
TELE.addData("Distance 1", s1D);
|
|
||||||
TELE.addData("Distance 2", s2D);
|
|
||||||
TELE.addData("Distance 3", s3D);
|
|
||||||
TELE.addData("B1", b1);
|
|
||||||
TELE.addData("B2", b2);
|
|
||||||
TELE.addData("B3", b3);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
flywheel = new FlywheelV2();
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
|
||||||
limelightManager.init();
|
|
||||||
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
if (gamepad2.dpadUpWasPressed()) {
|
|
||||||
hoodAuto -= 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadDownWasPressed()) {
|
|
||||||
hoodAuto += 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()){
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
}
|
|
||||||
|
|
||||||
double turrPID;
|
|
||||||
|
|
||||||
if (redAlliance){
|
|
||||||
turrPID = servo.setTurrPos(turret_detectRedClose);
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
} else {
|
|
||||||
turrPID = servo.setTurrPos(turret_detectBlueClose);
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
}
|
|
||||||
|
|
||||||
robot.turr1.setPower(turrPID);
|
|
||||||
robot.turr2.setPower(-turrPID);
|
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
|
||||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot0.build(),
|
|
||||||
initShooter(AUTO_CLOSE_VEL),
|
|
||||||
Obelisk()
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup1.build(),
|
|
||||||
intake(intake1Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot1.build(),
|
|
||||||
ColorDetect(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup2.build(),
|
|
||||||
intake(intake2Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot2.build(),
|
|
||||||
ColorDetect(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("finished");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
sleep(2000);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
//TODO: adjust this according to Teleop numbers
|
|
||||||
public void detectTag() {
|
|
||||||
limelightManager.update();
|
|
||||||
bearing = limelightManager.getBearing();
|
|
||||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
|
||||||
double turretPID = servo.setTurrPos(turretPos);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void shootingSequence() {
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
|
|
||||||
// Define sequences based on obelisk configuration
|
|
||||||
double[][] sequences = {
|
|
||||||
{1, 2, 3}, {1, 3, 2}, {2, 1, 3}, {2, 3, 1}, {3, 1, 2}, {3, 2, 1}
|
|
||||||
};
|
|
||||||
|
|
||||||
double[] sequence = null;
|
|
||||||
|
|
||||||
if (gpp) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 == b3) sequence = sequences[0]; // 1,2,3
|
|
||||||
else if (b2 == 2 && b1 == b3) sequence = sequences[2]; // 2,1,3
|
|
||||||
else if (b3 == 2 && b1 == b2) sequence = sequences[4]; // 3,1,2
|
|
||||||
else sequence = sequences[0];
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) sequence = sequences[0];
|
|
||||||
else if (b2 == 2) sequence = sequences[2];
|
|
||||||
else if (b3 == 2) sequence = sequences[4];
|
|
||||||
} else sequence = sequences[0];
|
|
||||||
} else if (pgp) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 == b3) sequence = sequences[2]; // 2,1,3
|
|
||||||
else if (b2 == 2 && b1 == b3) sequence = sequences[0]; // 1,2,3
|
|
||||||
else if (b3 == 2 && b1 == b2) sequence = sequences[3]; // 2,3,1
|
|
||||||
else sequence = sequences[0];
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) sequence = sequences[2];
|
|
||||||
else if (b2 == 2) sequence = sequences[0];
|
|
||||||
else if (b3 == 2) sequence = sequences[3];
|
|
||||||
} else sequence = sequences[2];
|
|
||||||
} else if (ppg) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 == b3) sequence = sequences[4]; // 3,1,2
|
|
||||||
else if (b2 == 2 && b1 == b3) sequence = sequences[5]; // 3,2,1
|
|
||||||
else if (b3 == 2 && b1 == b2) sequence = sequences[0]; // 1,2,3
|
|
||||||
else sequence = sequences[0];
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) sequence = sequences[4];
|
|
||||||
else if (b2 == 2) sequence = sequences[5];
|
|
||||||
else if (b3 == 2) sequence = sequences[0];
|
|
||||||
} else sequence = sequences[4];
|
|
||||||
} else sequence = sequences[0];
|
|
||||||
|
|
||||||
executeShootingSequence(sequence);
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
private void executeShootingSequence(double[] sequence) {
|
|
||||||
double[] ballPositions = {
|
|
||||||
spindexer_outtakeBall1,
|
|
||||||
spindexer_outtakeBall2,
|
|
||||||
spindexer_outtakeBall3
|
|
||||||
};
|
|
||||||
|
|
||||||
for (double ball : sequence) {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(ballPositions[(int) ball - 1], AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,619 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
import com.acmerobotics.roadrunner.ParallelAction;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.acmerobotics.roadrunner.SequentialAction;
|
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class AutoFar_V1 extends LinearOpMode {
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
FlywheelV2 flywheel;
|
|
||||||
Servos servo;
|
|
||||||
LimelightManager limelightManager;
|
|
||||||
|
|
||||||
double velo = 0.0;
|
|
||||||
public static double intake1Time = 2.7;
|
|
||||||
public static double intake2Time = 3.0;
|
|
||||||
public static double colorDetect = 3.0;
|
|
||||||
public static double holdTurrPow = 0.1;
|
|
||||||
|
|
||||||
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
|
||||||
int b1 = 0, b2 = 0, b3 = 0;
|
|
||||||
boolean gpp = false, pgp = false, ppg = false;
|
|
||||||
double powPID = 0.0;
|
|
||||||
double bearing = 0.0;
|
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !flywheel.getSteady();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action Obelisk() {
|
|
||||||
return new Action() {
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
limelightManager.update();
|
|
||||||
int id = limelightManager.detectFiducial();
|
|
||||||
|
|
||||||
if (id == 21) gpp = true;
|
|
||||||
else if (id == 22) pgp = true;
|
|
||||||
else if (id == 23) ppg = true;
|
|
||||||
|
|
||||||
TELE.addData("Fiducial ID", id);
|
|
||||||
TELE.addData("21", gpp);
|
|
||||||
TELE.addData("22", pgp);
|
|
||||||
TELE.addData("23", ppg);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (gpp || pgp || ppg) {
|
|
||||||
LimelightManager.LimelightMode mode = redAlliance ?
|
|
||||||
LimelightManager.LimelightMode.RED_GOAL :
|
|
||||||
LimelightManager.LimelightMode.BLUE_GOAL;
|
|
||||||
limelightManager.switchMode(mode);
|
|
||||||
|
|
||||||
double turretTarget = redAlliance ? turret_redFar : turret_blueFar;
|
|
||||||
double turretPID = servo.setTurrPos(turretTarget);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
return !servo.turretEqual(turretTarget);
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action spindex(double spindexer, int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double spinPID = 0.0;
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
|
||||||
robot.spin1.setPower(spinPID);
|
|
||||||
robot.spin2.setPower(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)){
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action Shoot(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double transferStamp = 0.0;
|
|
||||||
int ticker = 1;
|
|
||||||
boolean transferIn = false;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("shooting");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
detectTag();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
transferStamp = getRuntime();
|
|
||||||
ticker++;
|
|
||||||
}
|
|
||||||
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addData("ticker", ticker);
|
|
||||||
TELE.update();
|
|
||||||
transferIn = true;
|
|
||||||
return true;
|
|
||||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
robot.turr1.setPower(holdTurrPow);
|
|
||||||
robot.turr2.setPower(holdTurrPow);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("shot once");
|
|
||||||
TELE.update();
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
|
||||||
return new Action() {
|
|
||||||
double position = spindexer_intakePos1;
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
double pow = 1.0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
robot.intake.setPower(pow);
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
if (!servo.spinEqual(position)){
|
|
||||||
double spinPID = servo.setSpinPos(position);
|
|
||||||
robot.spin1.setPower(spinPID);
|
|
||||||
robot.spin2.setPower(-spinPID);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
|
||||||
if (s2D > 60){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
position = spindexer_intakePos2;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
position = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
position = spindexer_intakePos1;
|
|
||||||
}
|
|
||||||
} else if (s3D > 33){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
position = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
position = spindexer_intakePos1;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
position = spindexer_intakePos2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("Intaking");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
if (getRuntime() - stamp - intakeTime < 1){
|
|
||||||
pow = -2*(getRuntime() - stamp - intakeTime);
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action ColorDetect(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (s1D < 43) {
|
|
||||||
|
|
||||||
double green = robot.color1.getNormalizedColors().green;
|
|
||||||
double red = robot.color1.getNormalizedColors().red;
|
|
||||||
double blue = robot.color1.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b1 = 2;
|
|
||||||
} else {
|
|
||||||
b1 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s2D < 60) {
|
|
||||||
|
|
||||||
double green = robot.color2.getNormalizedColors().green;
|
|
||||||
double red = robot.color2.getNormalizedColors().red;
|
|
||||||
double blue = robot.color2.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b2 = 2;
|
|
||||||
} else {
|
|
||||||
b2 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s3D < 33) {
|
|
||||||
|
|
||||||
double green = robot.color3.getNormalizedColors().green;
|
|
||||||
double red = robot.color3.getNormalizedColors().red;
|
|
||||||
double blue = robot.color3.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b3 = 2;
|
|
||||||
} else {
|
|
||||||
b3 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("Detecting");
|
|
||||||
TELE.addData("Distance 1", s1D);
|
|
||||||
TELE.addData("Distance 2", s2D);
|
|
||||||
TELE.addData("Distance 3", s3D);
|
|
||||||
TELE.addData("B1", b1);
|
|
||||||
TELE.addData("B2", b2);
|
|
||||||
TELE.addData("B3", b3);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
flywheel = new FlywheelV2();
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
|
||||||
limelightManager.init();
|
|
||||||
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
|
||||||
|
|
||||||
//TODO: add positions to develop auto
|
|
||||||
|
|
||||||
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(0,0,0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rfx1, rfy1), rfh1);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
if (gamepad2.dpadUpWasPressed()) {
|
|
||||||
hoodAuto -= 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadDownWasPressed()) {
|
|
||||||
hoodAuto += 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()){
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
}
|
|
||||||
|
|
||||||
double turrPID;
|
|
||||||
|
|
||||||
if (redAlliance){
|
|
||||||
turrPID = servo.setTurrPos(turret_detectRedClose);
|
|
||||||
} else {
|
|
||||||
turrPID = servo.setTurrPos(turret_detectBlueClose);
|
|
||||||
}
|
|
||||||
|
|
||||||
robot.turr1.setPower(turrPID);
|
|
||||||
robot.turr2.setPower(-turrPID);
|
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAutoFar);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
|
||||||
TELE.addData("Spin Pos", servo.getSpinPos());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
initShooter(AUTO_FAR_VEL),
|
|
||||||
Obelisk()
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(park.build());
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("finished");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
sleep(2000);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
//TODO: adjust this according to Teleop numbers
|
|
||||||
public void detectTag() {
|
|
||||||
limelightManager.update();
|
|
||||||
bearing = limelightManager.getBearing();
|
|
||||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
|
||||||
double turretPID = servo.setTurrPos(turretPos);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void shootingSequence() {
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
if (gpp) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 - b3 == 0) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
|
||||||
sequence3();
|
|
||||||
TELE.addLine("sequence3");
|
|
||||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
|
||||||
sequence6();
|
|
||||||
TELE.addLine("sequence6");
|
|
||||||
} else {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
} else if (b2 == 2) {
|
|
||||||
sequence3();
|
|
||||||
TELE.addLine("sequence3");
|
|
||||||
} else if (b3 == 2) {
|
|
||||||
sequence6();
|
|
||||||
TELE.addLine("sequence6");
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
} else if (pgp) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 - b3 == 0) {
|
|
||||||
sequence3();
|
|
||||||
TELE.addLine("sequence3");
|
|
||||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
|
||||||
sequence4();
|
|
||||||
TELE.addLine("sequence4");
|
|
||||||
} else {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) {
|
|
||||||
sequence3();
|
|
||||||
TELE.addLine("sequence3");
|
|
||||||
} else if (b2 == 2) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
} else if (b3 == 2) {
|
|
||||||
sequence4();
|
|
||||||
TELE.addLine("sequence4");
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
sequence3();
|
|
||||||
TELE.addLine("sequence3");
|
|
||||||
}
|
|
||||||
} else if (ppg) {
|
|
||||||
if (b1 + b2 + b3 == 4) {
|
|
||||||
if (b1 == 2 && b2 - b3 == 0) {
|
|
||||||
sequence6();
|
|
||||||
TELE.addLine("sequence6");
|
|
||||||
} else if (b2 == 2 && b1 - b3 == 0) {
|
|
||||||
sequence5();
|
|
||||||
TELE.addLine("sequence5");
|
|
||||||
} else if (b3 == 2 && b1 - b2 == 0) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
} else {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
} else if (b1 + b2 + b3 >= 5) {
|
|
||||||
if (b1 == 2) {
|
|
||||||
sequence6();
|
|
||||||
TELE.addLine("sequence6");
|
|
||||||
} else if (b2 == 2) {
|
|
||||||
sequence5();
|
|
||||||
TELE.addLine("sequence5");
|
|
||||||
} else if (b3 == 2) {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
sequence6();
|
|
||||||
TELE.addLine("sequence6");
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
sequence1();
|
|
||||||
TELE.addLine("sequence1");
|
|
||||||
}
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence1() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence2() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence3() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence4() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence5() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence6() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
|
||||||
Shoot(AUTO_FAR_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -3,9 +3,8 @@ package org.firstinspires.ftc.teamcode.autonomous;
|
|||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.*;
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
@@ -178,8 +177,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (gpp || pgp || ppg){
|
if (gpp || pgp || ppg){
|
||||||
robot.turr1.setPower(turret_blueClose);
|
robot.turr1.setPosition(turret_blue);
|
||||||
robot.turr2.setPower(1 - turret_blueClose);
|
robot.turr2.setPosition(1 - turret_blue);
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -203,8 +202,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
position = spindexer_intakePos1 - 0.02;
|
position = spindexer_intakePos1 - 0.02;
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.spin1.setPower(position);
|
robot.spin1.setPosition(position);
|
||||||
robot.spin2.setPower(1 - position);
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = getRuntime();
|
stamp = getRuntime();
|
||||||
@@ -264,8 +263,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
robot.spin1.setPower(spindexer);
|
robot.spin1.setPosition(spindexer);
|
||||||
robot.spin2.setPower(1-spindexer);
|
robot.spin2.setPosition(1-spindexer);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -380,8 +379,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
position = spindexer_intakePos1 - 0.02;
|
position = spindexer_intakePos1 - 0.02;
|
||||||
}
|
}
|
||||||
robot.spin1.setPower(position);
|
robot.spin1.setPosition(position);
|
||||||
robot.spin2.setPower(1 - position);
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("Intaking");
|
TELE.addLine("Intaking");
|
||||||
@@ -418,8 +417,8 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
position = spindexer_intakePos1 - 0.02;
|
position = spindexer_intakePos1 - 0.02;
|
||||||
}
|
}
|
||||||
robot.spin1.setPower(position);
|
robot.spin1.setPosition(position);
|
||||||
robot.spin2.setPower(1 - position);
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
@@ -541,13 +540,13 @@ public class Blue_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
robot.turr1.setPower(turret_detectBlueClose);
|
robot.turr1.setPosition(turret_detectBlue);
|
||||||
robot.turr2.setPower(1 - turret_detectBlueClose);
|
robot.turr2.setPosition(1 - turret_detectBlue);
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
robot.spin1.setPower(spindexer_intakePos1);
|
robot.spin1.setPosition(spindexer_intakePos1);
|
||||||
robot.spin2.setPower(1 - spindexer_intakePos1);
|
robot.spin2.setPosition(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
aprilTag.update();
|
aprilTag.update();
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
|
|||||||
@@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.autonomous;
|
|||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.*;
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
@@ -25,8 +26,6 @@ import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@Autonomous(preselectTeleOp = "TeleopV2")
|
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||||
@@ -42,9 +41,8 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
|
|
||||||
Servos servo;
|
|
||||||
|
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
public static double intake1Time = 2.9;
|
public static double intake1Time = 2.9;
|
||||||
|
|
||||||
public static double intake2Time = 2.9;
|
public static double intake2Time = 2.9;
|
||||||
@@ -59,33 +57,42 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
double powPID = 0.0;
|
double powPID = 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
|
||||||
|
|
||||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
boolean spindexPosEqual(double spindexer) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex equal");
|
||||||
|
TELE.update();
|
||||||
|
return (scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01 &&
|
||||||
|
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||||
|
}
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
public Action initShooter(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
|
double initPos = 0.0;
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
double stamp1 = 0.0;
|
double stamp1 = 0.0;
|
||||||
double ticker = 0.0;
|
double ticker = 0.0;
|
||||||
double stamp2 = 0.0;
|
double stamp2 = 0.0;
|
||||||
|
double currentPos = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp2 = getRuntime();
|
stamp2 = getRuntime();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
targetVelocity = (double) vel;
|
||||||
ticker++;
|
ticker++;
|
||||||
if (ticker % 16 == 0) {
|
if (ticker % 16 == 0) {
|
||||||
stamp = getRuntime();
|
stamp = getRuntime();
|
||||||
stamp1 = stamp;
|
stamp1 = stamp;
|
||||||
}
|
}
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
@@ -114,7 +121,7 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
steady = flywheel.getSteady();
|
steady = flywheel.getSteady();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
@@ -123,7 +130,7 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.update();
|
TELE.update();
|
||||||
detectTag();
|
|
||||||
|
|
||||||
if (last && !steady){
|
if (last && !steady){
|
||||||
stamp = getRuntime();
|
stamp = getRuntime();
|
||||||
@@ -169,10 +176,9 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
if (gpp || pgp || ppg){
|
if (gpp || pgp || ppg){
|
||||||
double turretPID = servo.setTurrPos(turret_redClose);
|
robot.turr1.setPosition(turret_red);
|
||||||
robot.turr1.setPower(turretPID);
|
robot.turr2.setPosition(1 - turret_red);
|
||||||
robot.turr2.setPower(-turretPID);
|
return false;
|
||||||
return !servo.turretEqual(turret_redClose);
|
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -180,17 +186,51 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action spindex (double spindexer, int vel){
|
public Action spindex (double spindexer, double vel){
|
||||||
return new Action() {
|
return new Action() {
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
robot.spin1.setPower(spindexer);
|
robot.spin1.setPosition(spindexer);
|
||||||
robot.spin2.setPower(1-spindexer);
|
robot.spin2.setPosition(1-spindexer);
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("spindex");
|
TELE.addLine("spindex");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -199,32 +239,65 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
return !servo.spinEqual(spindexer);
|
return !spindexPosEqual(spindexer);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action Shoot(int vel) {
|
public Action Shoot(double vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
double transferStamp = 0.0;
|
double transferStamp = 0.0;
|
||||||
int ticker = 1;
|
int ticker = 1;
|
||||||
boolean transferIn = false;
|
boolean transferIn = false;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("shooting");
|
TELE.addLine("shooting");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
detectTag();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
if (ticker == 1) {
|
||||||
transferStamp = getRuntime();
|
transferStamp = getRuntime();
|
||||||
ticker++;
|
ticker++;
|
||||||
@@ -272,8 +345,8 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
position = spindexer_intakePos1 - 0.02;
|
position = spindexer_intakePos1 - 0.02;
|
||||||
}
|
}
|
||||||
robot.spin1.setPower(position);
|
robot.spin1.setPosition(position);
|
||||||
robot.spin2.setPower(1 - position);
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addLine("Intaking");
|
TELE.addLine("Intaking");
|
||||||
@@ -331,8 +404,8 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
position = spindexer_intakePos1 - 0.02;
|
position = spindexer_intakePos1 - 0.02;
|
||||||
}
|
}
|
||||||
robot.spin1.setPower(position);
|
robot.spin1.setPosition(position);
|
||||||
robot.spin2.setPower(1 - position);
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
@@ -454,14 +527,16 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turret_detectRed);
|
||||||
|
robot.turr2.setPosition(1 - turret_detectRed);
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
robot.spin1.setPower(spindexer_intakePos1);
|
robot.spin1.setPosition(spindexer_intakePos1);
|
||||||
robot.spin2.setPower(1 - spindexer_intakePos1);
|
robot.spin2.setPosition(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
aprilTag.update();
|
aprilTag.update();
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.addData("Turret Pos", servo.getTurrPos());
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -485,7 +560,7 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
@@ -521,7 +596,7 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
@@ -551,7 +626,7 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
velo = flywheel.getVelo();
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
@@ -572,25 +647,6 @@ public class Red_V2 extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public void detectTag(){
|
|
||||||
AprilTagDetection d20 = aprilTag.getTagById(20);
|
|
||||||
AprilTagDetection d24 = aprilTag.getTagById(24);
|
|
||||||
|
|
||||||
if (d20 != null) {
|
|
||||||
bearing = d20.ftcPose.bearing;
|
|
||||||
TELE.addData("Bear", bearing);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (d24 != null) {
|
|
||||||
bearing = d24.ftcPose.bearing;
|
|
||||||
TELE.addData("Bear", bearing);
|
|
||||||
}
|
|
||||||
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
|
||||||
double turretPID = servo.setTurrPos(turretPos);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void shootingSequence() {
|
public void shootingSequence() {
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
if (gpp) {
|
if (gpp) {
|
||||||
|
|||||||
@@ -1,5 +1,4 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
public class Color {
|
public class Color {
|
||||||
public static boolean redAlliance = true;
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,21 +12,39 @@ public class Poses {
|
|||||||
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
|
public static double x1 = 50, y1 = 0, h1 = 0;
|
||||||
|
|
||||||
|
public static double x2 = 31, y2 = 32, h2 = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double x2_b = 58, y2_b = 42, h2_b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double x3 = 34, y3 = 58, h3 = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double tx = 0, ty = 0, th = 0;
|
||||||
|
|
||||||
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
||||||
|
|
||||||
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
||||||
|
|
||||||
public static double rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
public static double rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
||||||
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
|
||||||
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
|
||||||
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
|
||||||
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
|
||||||
|
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
|
|
||||||
|
|||||||
@@ -5,16 +5,16 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.34;
|
public static double spindexer_intakePos1 = 0.665;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.5;
|
public static double spindexer_intakePos3 = 0.29;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.66;
|
public static double spindexer_intakePos2 = 0.99;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.42;
|
public static double spindexer_outtakeBall3 = 0.845;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.74;
|
public static double spindexer_outtakeBall2 = 0.48;
|
||||||
public static double spindexer_outtakeBall1 = 0.58;
|
public static double spindexer_outtakeBall1 = 0.1;
|
||||||
|
|
||||||
public static double transferServo_out = 0.15;
|
public static double transferServo_out = 0.15;
|
||||||
|
|
||||||
@@ -26,20 +26,16 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double hoodAuto = 0.55;
|
public static double hoodAuto = 0.55;
|
||||||
|
|
||||||
public static double hoodAutoFar = 0.5; //TODO: change this;
|
public static double hoodHigh = 0.21;
|
||||||
|
|
||||||
public static double hoodHigh = 0.21; //TODO: change this;
|
public static double hoodLow = 1.0;
|
||||||
|
|
||||||
public static double hoodLow = 1.0; //TODO: change this;
|
public static double turret_red = 0.42;
|
||||||
|
public static double turret_blue = 0.38;
|
||||||
|
|
||||||
public static double turret_redClose = 0.42;
|
public static double turret_detectRed = 0.2;
|
||||||
public static double turret_blueClose = 0.38;
|
|
||||||
public static double turret_redFar = 0.5; //TODO: change this
|
|
||||||
public static double turret_blueFar = 0.5; // TODO: change this
|
|
||||||
|
|
||||||
public static double turret_detectRedClose = 0.2;
|
public static double turret_detectBlue = 0.6;
|
||||||
|
|
||||||
public static double turret_detectBlueClose = 0.6;
|
|
||||||
public static double turrDefault = 0.40;
|
public static double turrDefault = 0.40;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -20,5 +20,4 @@ public class ShooterVars {
|
|||||||
|
|
||||||
// VELOCITY CONSTANTS
|
// VELOCITY CONSTANTS
|
||||||
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
|
||||||
}
|
}
|
||||||
@@ -1,9 +1,19 @@
|
|||||||
package org.firstinspires.ftc.teamcode.teleop;
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turrDefault;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransfer;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.waitTransferOut;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.ShooterTest.kP;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.ShooterTest.maxStep;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.restPos;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.PositionalServoProgrammer.scalar;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
@@ -16,9 +26,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
import java.util.ArrayList;
|
import java.util.ArrayList;
|
||||||
@@ -27,8 +35,7 @@ import java.util.List;
|
|||||||
@TeleOp
|
@TeleOp
|
||||||
@Config
|
@Config
|
||||||
public class TeleopV2 extends LinearOpMode {
|
public class TeleopV2 extends LinearOpMode {
|
||||||
Servos servo;
|
|
||||||
Flywheel flywheel;
|
|
||||||
public static double manualVel = 3000;
|
public static double manualVel = 3000;
|
||||||
public static double hood = 0.5;
|
public static double hood = 0.5;
|
||||||
public static double hoodDefaultPos = 0.5;
|
public static double hoodDefaultPos = 0.5;
|
||||||
@@ -56,7 +63,6 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
double yOffset = 0.0;
|
double yOffset = 0.0;
|
||||||
double headingOffset = 0.0;
|
double headingOffset = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
int camTicker = 0;
|
|
||||||
List<Double> s1G = new ArrayList<>();
|
List<Double> s1G = new ArrayList<>();
|
||||||
List<Double> s2G = new ArrayList<>();
|
List<Double> s2G = new ArrayList<>();
|
||||||
List<Double> s3G = new ArrayList<>();
|
List<Double> s3G = new ArrayList<>();
|
||||||
@@ -92,11 +98,6 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
private double transferStamp = 0.0;
|
private double transferStamp = 0.0;
|
||||||
private int tickerA = 1;
|
private int tickerA = 1;
|
||||||
private boolean transferIn = false;
|
private boolean transferIn = false;
|
||||||
double turretPID = 0.0;
|
|
||||||
double turretPos = 0.5;
|
|
||||||
double spindexPID = 0.0;
|
|
||||||
double spindexPos = spindexer_intakePos1;
|
|
||||||
double error = 0.0;
|
|
||||||
|
|
||||||
public static double velPrediction(double distance) {
|
public static double velPrediction(double distance) {
|
||||||
|
|
||||||
@@ -128,8 +129,6 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
TELE = new MultipleTelemetry(
|
TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
);
|
);
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
flywheel = new Flywheel();
|
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
@@ -137,6 +136,9 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
||||||
|
|
||||||
|
robot.turr1.setPosition(0.4);
|
||||||
|
robot.turr2.setPosition(1 - 0.4);
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
@@ -158,21 +160,6 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
robot.frontRight.setPower(frontRightPower);
|
robot.frontRight.setPower(frontRightPower);
|
||||||
robot.backRight.setPower(backRightPower);
|
robot.backRight.setPower(backRightPower);
|
||||||
|
|
||||||
// PID SERVOS
|
|
||||||
turretPID = servo.setTurrPos(turretPos);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
|
|
||||||
//TODO: make sure changing position works throughout opmode
|
|
||||||
if (!servo.spinEqual(spindexPos)){
|
|
||||||
spindexPID = servo.setSpinPos(spindexPos);
|
|
||||||
robot.spin1.setPower(spindexPID);
|
|
||||||
robot.spin2.setPower(-spindexPID);
|
|
||||||
} else{
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
//INTAKE:
|
//INTAKE:
|
||||||
|
|
||||||
if (gamepad1.rightBumperWasPressed()) {
|
if (gamepad1.rightBumperWasPressed()) {
|
||||||
@@ -196,15 +183,22 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
robot.intake.setPower(1);
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
double position;
|
||||||
|
|
||||||
if ((getRuntime() % 0.3) > 0.15) {
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
spindexPos = spindexer_intakePos1 + 0.015;
|
position = spindexer_intakePos1 + 0.015;
|
||||||
} else {
|
} else {
|
||||||
spindexPos = spindexer_intakePos1 - 0.015;
|
position = spindexer_intakePos1 - 0.015;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1 - position);
|
||||||
|
|
||||||
} else if (reject) {
|
} else if (reject) {
|
||||||
robot.intake.setPower(-1);
|
robot.intake.setPower(-1);
|
||||||
spindexPos = spindexer_intakePos1;
|
double position = spindexer_intakePos1;
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1 - position);
|
||||||
} else {
|
} else {
|
||||||
robot.intake.setPower(0);
|
robot.intake.setPower(0);
|
||||||
}
|
}
|
||||||
@@ -286,7 +280,46 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
//SHOOTER:
|
//SHOOTER:
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
double penguin = 0;
|
||||||
|
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
penguin = (double) robot.shooterEncoder.getCurrentPosition() / 2048;
|
||||||
|
double stamp = getRuntime();
|
||||||
|
velo1 = -60 * ((penguin - initPos) / (stamp - stamp1));
|
||||||
|
initPos = penguin;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
velo = velo1;
|
||||||
|
|
||||||
|
double feed = vel / 4500;
|
||||||
|
|
||||||
|
if (vel > 500) {
|
||||||
|
feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
}
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo1;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
double powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
|
||||||
|
if (vel - velo > 1000) {
|
||||||
|
powPID = 1;
|
||||||
|
} else if (velo - vel > 1000) {
|
||||||
|
powPID = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("PIDPower", powPID);
|
||||||
|
|
||||||
|
TELE.addData("vel", velo1);
|
||||||
|
|
||||||
robot.shooter1.setPower(powPID);
|
robot.shooter1.setPower(powPID);
|
||||||
robot.shooter2.setPower(powPID);
|
robot.shooter2.setPower(powPID);
|
||||||
@@ -322,8 +355,7 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
offset -= 360;
|
offset -= 360;
|
||||||
}
|
}
|
||||||
|
|
||||||
//TODO: test the camera teleop code
|
double pos = turrDefault;
|
||||||
double pos = turrDefault + (error/8); // adds the overall error to the default
|
|
||||||
|
|
||||||
TELE.addData("offset", offset);
|
TELE.addData("offset", offset);
|
||||||
|
|
||||||
@@ -335,51 +367,14 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
pos = 0.97;
|
pos = 0.97;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1){ //not moving
|
|
||||||
AprilTagDetection d20 = aprilTagWebcam.getTagById(20);
|
|
||||||
AprilTagDetection d24 = aprilTagWebcam.getTagById(24);
|
|
||||||
|
|
||||||
double bearing = 0.0;
|
|
||||||
if (d20 != null || d24 != null){
|
|
||||||
if (d20 != null) {
|
|
||||||
bearing = d20.ftcPose.bearing;
|
|
||||||
}
|
|
||||||
if (d24 != null) {
|
|
||||||
bearing = d24.ftcPose.bearing;
|
|
||||||
}
|
|
||||||
overrideTurr = true;
|
|
||||||
turretPos = servo.getTurrPos() - (bearing/1300);
|
|
||||||
TELE.addData("Bear", bearing);
|
|
||||||
|
|
||||||
double bearingCorrection = bearing / 1300;
|
|
||||||
|
|
||||||
|
|
||||||
// deadband: ignore tiny noise
|
|
||||||
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
|
||||||
|
|
||||||
// only accumulate if bearing direction is consistent
|
|
||||||
if (Math.signum(bearingCorrection) == Math.signum(error) || error == 0) {
|
|
||||||
error += bearingCorrection;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
camTicker++;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
|
||||||
camTicker = 0;
|
|
||||||
overrideTurr = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (manualTurret) {
|
if (manualTurret) {
|
||||||
pos = turrDefault + (manualOffset / 100);
|
pos = turrDefault + (manualOffset / 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!overrideTurr) {
|
if (!overrideTurr) {
|
||||||
turretPos = pos;
|
|
||||||
|
robot.turr1.setPosition(pos);
|
||||||
|
robot.turr2.setPosition(1 - pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad2.dpad_right) {
|
if (gamepad2.dpad_right) {
|
||||||
@@ -460,9 +455,12 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
reject = true;
|
reject = true;
|
||||||
|
|
||||||
if (getRuntime() % 3 > 1.5) {
|
if (getRuntime() % 3 > 1.5) {
|
||||||
spindexPos = 1;
|
robot.spin1.setPosition(0);
|
||||||
|
robot.spin2.setPosition(1);
|
||||||
} else {
|
} else {
|
||||||
spindexPos = 0;
|
|
||||||
|
robot.spin1.setPosition(1);
|
||||||
|
robot.spin2.setPosition(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
@@ -480,14 +478,39 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
||||||
boolean shootingDone = false;
|
boolean shootingDone = false;
|
||||||
|
|
||||||
|
AprilTagDetection d20 = aprilTagWebcam.getTagById(20);
|
||||||
|
AprilTagDetection d24 = aprilTagWebcam.getTagById(24);
|
||||||
|
|
||||||
|
if (d20 != null) {
|
||||||
|
overrideTurr = true;
|
||||||
|
double bearing = d20.ftcPose.bearing;
|
||||||
|
|
||||||
|
double finalPos = robot.turr1.getPosition() - (bearing / 1300);
|
||||||
|
robot.turr1.setPosition(finalPos);
|
||||||
|
robot.turr2.setPosition(1 - finalPos);
|
||||||
|
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (d24 != null) {
|
||||||
|
overrideTurr = true;
|
||||||
|
|
||||||
|
double bearing = d24.ftcPose.bearing;
|
||||||
|
double finalPos = robot.turr1.getPosition() - (bearing / 1300);
|
||||||
|
robot.turr1.setPosition(finalPos);
|
||||||
|
robot.turr2.setPosition(1 - finalPos);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
if (!outtake1) {
|
if (!outtake1) {
|
||||||
outtake1 = (servo.spinEqual(spindexer_outtakeBall1));
|
outtake1 = (spindexPosEqual(spindexer_outtakeBall1));
|
||||||
}
|
}
|
||||||
if (!outtake2) {
|
if (!outtake2) {
|
||||||
outtake2 = (servo.spinEqual(spindexer_outtakeBall2));
|
outtake2 = (spindexPosEqual(spindexer_outtakeBall2));
|
||||||
}
|
}
|
||||||
if (!outtake3) {
|
if (!outtake3) {
|
||||||
outtake3 = (servo.spinEqual(spindexer_outtakeBall3));
|
outtake3 = (spindexPosEqual(spindexer_outtakeBall3));
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (currentSlot) {
|
switch (currentSlot) {
|
||||||
@@ -530,7 +553,8 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
} else {
|
} else {
|
||||||
// Finished shooting all balls
|
// Finished shooting all balls
|
||||||
spindexPos = spindexer_intakePos1;
|
robot.spin1.setPosition(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_intakePos1);
|
||||||
shootA = true;
|
shootA = true;
|
||||||
shootB = true;
|
shootB = true;
|
||||||
shootC = true;
|
shootC = true;
|
||||||
@@ -743,9 +767,15 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
return countTrue > countWindow / 2.0; // more than 50% true
|
return countTrue > countWindow / 2.0; // more than 50% true
|
||||||
}
|
}
|
||||||
|
|
||||||
|
boolean spindexPosEqual(double spindexer) {
|
||||||
|
return (scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01 &&
|
||||||
|
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||||
|
}
|
||||||
|
|
||||||
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
||||||
// Set spin positions
|
// Set spin positions
|
||||||
spindexPos = spindexer;
|
robot.spin1.setPosition(spindexer);
|
||||||
|
robot.spin2.setPosition(1 - spindexer);
|
||||||
|
|
||||||
// Check if spindexer has reached the target position
|
// Check if spindexer has reached the target position
|
||||||
if (spinOk || getRuntime() - stamp > 1.5) {
|
if (spinOk || getRuntime() - stamp > 1.5) {
|
||||||
@@ -900,4 +930,9 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
return true; // default
|
return true; // default
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public double turretPos() {
|
||||||
|
return (scalar * ((robot.turr1Pos.getVoltage() - restPos) / 3.3));
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,797 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.teleop;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.qualcomm.hardware.lynx.LynxModule;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
|
|
||||||
import java.util.ArrayList;
|
|
||||||
import java.util.List;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
|
||||||
public class TeleopV3 extends LinearOpMode {
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
Servos servo;
|
|
||||||
Flywheel flywheel;
|
|
||||||
MecanumDrive drive;
|
|
||||||
LimelightManager limelightManager;
|
|
||||||
|
|
||||||
public static double manualVel = 3000;
|
|
||||||
public static double hoodDefaultPos = 0.5;
|
|
||||||
public static double desiredTurretAngle = 180;
|
|
||||||
public static double shootStamp2 = 0.0;
|
|
||||||
public double vel = 3000;
|
|
||||||
public boolean autoVel = true;
|
|
||||||
public double manualOffset = 0.0;
|
|
||||||
public boolean autoHood = true;
|
|
||||||
public boolean green1 = false;
|
|
||||||
public boolean green2 = false;
|
|
||||||
public boolean green3 = false;
|
|
||||||
public double shootStamp = 0.0;
|
|
||||||
public boolean circle = false;
|
|
||||||
public boolean square = false;
|
|
||||||
public boolean triangle = false;
|
|
||||||
double autoHoodOffset = 0.0;
|
|
||||||
boolean intake = false;
|
|
||||||
boolean reject = false;
|
|
||||||
double xOffset = 0.0;
|
|
||||||
double yOffset = 0.0;
|
|
||||||
double headingOffset = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
int camTicker = 0;
|
|
||||||
List<Double> s1G = new ArrayList<>();
|
|
||||||
List<Double> s2G = new ArrayList<>();
|
|
||||||
List<Double> s3G = new ArrayList<>();
|
|
||||||
List<Double> s1T = new ArrayList<>();
|
|
||||||
List<Double> s2T = new ArrayList<>();
|
|
||||||
List<Double> s3T = new ArrayList<>();
|
|
||||||
List<Boolean> s1 = new ArrayList<>();
|
|
||||||
List<Boolean> s2 = new ArrayList<>();
|
|
||||||
List<Boolean> s3 = new ArrayList<>();
|
|
||||||
boolean oddBallColor = false;
|
|
||||||
double hoodOffset = 0.0;
|
|
||||||
boolean shootA = true;
|
|
||||||
boolean shootB = true;
|
|
||||||
boolean shootC = true;
|
|
||||||
boolean manualTurret = false;
|
|
||||||
List<Integer> shootOrder = new ArrayList<>();
|
|
||||||
boolean outtake1 = false;
|
|
||||||
boolean outtake2 = false;
|
|
||||||
boolean outtake3 = false;
|
|
||||||
boolean overrideTurr = false;
|
|
||||||
private boolean shootAll = false;
|
|
||||||
private double transferStamp = 0.0;
|
|
||||||
private int tickerA = 1;
|
|
||||||
private boolean transferIn = false;
|
|
||||||
double turretPID = 0.0;
|
|
||||||
double turretPos = 0.5;
|
|
||||||
double spindexPID = 0.0;
|
|
||||||
double spindexPos = spindexer_intakePos1;
|
|
||||||
double error = 0.0;
|
|
||||||
double spinCurrentPos = 0.0, spinInitPos = 0.0, intakeStamp = 0.0, spinningPow = 0.15;
|
|
||||||
boolean reverse = false;
|
|
||||||
int intakeTicker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
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();
|
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
|
||||||
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
|
||||||
limelightManager.init();
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
limelightManager.switchMode(LimelightManager.LimelightMode.RED_GOAL);
|
|
||||||
} else {
|
|
||||||
limelightManager.switchMode(LimelightManager.LimelightMode.BLUE_GOAL);
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
while (opModeIsActive()) {
|
|
||||||
//DRIVETRAIN:
|
|
||||||
|
|
||||||
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
|
||||||
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
|
||||||
double rx = gamepad1.left_stick_x;
|
|
||||||
|
|
||||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
|
||||||
double frontLeftPower = (y + x + rx) / denominator;
|
|
||||||
double backLeftPower = (y - x + rx) / denominator;
|
|
||||||
double frontRightPower = (y - x - rx) / denominator;
|
|
||||||
double backRightPower = (y + x - rx) / denominator;
|
|
||||||
|
|
||||||
robot.frontLeft.setPower(frontLeftPower);
|
|
||||||
robot.backLeft.setPower(backLeftPower);
|
|
||||||
robot.frontRight.setPower(frontRightPower);
|
|
||||||
robot.backRight.setPower(backRightPower);
|
|
||||||
|
|
||||||
// PID SERVOS
|
|
||||||
turretPID = servo.setTurrPos(turretPos);
|
|
||||||
robot.turr1.setPower(turretPID);
|
|
||||||
robot.turr2.setPower(-turretPID);
|
|
||||||
|
|
||||||
if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) {
|
|
||||||
spindexPID = servo.setSpinPos(spindexPos);
|
|
||||||
robot.spin1.setPower(spindexPID);
|
|
||||||
robot.spin2.setPower(-spindexPID);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// INTAKE
|
|
||||||
if (gamepad1.right_bumper) {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
intakeTicker++;
|
|
||||||
if (intakeTicker % 16 == 0) {
|
|
||||||
spinCurrentPos = servo.getSpinPos();
|
|
||||||
if (Math.abs(spinCurrentPos - spinInitPos) == 0.0) {
|
|
||||||
reverse = !reverse;
|
|
||||||
}
|
|
||||||
spinInitPos = spinCurrentPos;
|
|
||||||
}
|
|
||||||
if (reverse) {
|
|
||||||
robot.spin1.setPower(spinningPow);
|
|
||||||
robot.spin2.setPower(-spinningPow);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPower(-spinningPow);
|
|
||||||
robot.spin2.setPower(spinningPow);
|
|
||||||
}
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
intakeStamp = getRuntime();
|
|
||||||
TELE.addData("Reverse?", reverse);
|
|
||||||
TELE.update();
|
|
||||||
} else if (gamepad1.left_bumper) {
|
|
||||||
robot.intake.setPower(-(getRuntime() - intakeStamp) * 2);
|
|
||||||
spindexPos = spindexer_intakePos2;
|
|
||||||
intakeTicker = 0;
|
|
||||||
} else {
|
|
||||||
if (getRuntime() - intakeStamp < 1) {
|
|
||||||
robot.intake.setPower(-(getRuntime() - intakeStamp) * 2);
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
}
|
|
||||||
intakeTicker = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
//COLOR:
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
if (s1D < 43) {
|
|
||||||
|
|
||||||
double green = robot.color1.getNormalizedColors().green;
|
|
||||||
double red = robot.color1.getNormalizedColors().red;
|
|
||||||
double blue = robot.color1.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
s1G.add(gP);
|
|
||||||
|
|
||||||
if (gP >= 0.43) {
|
|
||||||
s1.add(true);
|
|
||||||
} else {
|
|
||||||
s1.add(false);
|
|
||||||
}
|
|
||||||
|
|
||||||
s1T.add(getRuntime());
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s2D < 60) {
|
|
||||||
|
|
||||||
double green = robot.color2.getNormalizedColors().green;
|
|
||||||
double red = robot.color2.getNormalizedColors().red;
|
|
||||||
double blue = robot.color2.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
s2G.add(gP);
|
|
||||||
|
|
||||||
if (gP >= 0.43) {
|
|
||||||
s2.add(true);
|
|
||||||
} else {
|
|
||||||
s2.add(false);
|
|
||||||
}
|
|
||||||
|
|
||||||
s2T.add(getRuntime());
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s3D < 33) {
|
|
||||||
|
|
||||||
double green = robot.color3.getNormalizedColors().green;
|
|
||||||
double red = robot.color3.getNormalizedColors().red;
|
|
||||||
double blue = robot.color3.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
s3G.add(gP);
|
|
||||||
|
|
||||||
if (gP >= 0.43) {
|
|
||||||
s3.add(true);
|
|
||||||
} else {
|
|
||||||
s3.add(false);
|
|
||||||
}
|
|
||||||
|
|
||||||
s3T.add(getRuntime());
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!s1.isEmpty()) {
|
|
||||||
green1 = checkGreen(s1, s1T);
|
|
||||||
}
|
|
||||||
if (!s2.isEmpty()) {
|
|
||||||
green2 = checkGreen(s2, s2T);
|
|
||||||
|
|
||||||
}
|
|
||||||
if (!s3.isEmpty()) {
|
|
||||||
green3 = checkGreen(s3, s3T);
|
|
||||||
}
|
|
||||||
|
|
||||||
//SHOOTER:
|
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
|
||||||
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
double offset;
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotX = robX - xOffset;
|
|
||||||
double robotY = robY - yOffset;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -10;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = goalX - robotX; // delta x from robot to goal
|
|
||||||
double dy = goalY - robotY; // delta y from robot to goal
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
|
||||||
|
|
||||||
desiredTurretAngle += manualOffset;
|
|
||||||
|
|
||||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
|
||||||
|
|
||||||
if (offset > 135) {
|
|
||||||
offset -= 360;
|
|
||||||
}
|
|
||||||
|
|
||||||
//TODO: test the camera teleop code
|
|
||||||
double pos = turrDefault + (error / 8); // adds the overall error to the default
|
|
||||||
|
|
||||||
TELE.addData("offset", offset);
|
|
||||||
|
|
||||||
pos -= offset * (0.9 / 360);
|
|
||||||
|
|
||||||
if (pos < 0.02) {
|
|
||||||
pos = 0.02;
|
|
||||||
} else if (pos > 0.97) {
|
|
||||||
pos = 0.97;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1) { //not moving
|
|
||||||
limelightManager.update();
|
|
||||||
double bearing = limelightManager.getBearing();
|
|
||||||
|
|
||||||
if (limelightManager.getLatestResult() != null && limelightManager.getLatestResult().isValid()) {
|
|
||||||
overrideTurr = true;
|
|
||||||
turretPos = servo.getTurrPos() - (bearing / 1300);
|
|
||||||
|
|
||||||
double bearingCorrection = bearing / 1300;
|
|
||||||
|
|
||||||
// deadband: ignore tiny noise
|
|
||||||
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
|
||||||
// only accumulate if bearing direction is consistent
|
|
||||||
if (Math.signum(bearingCorrection) == Math.signum(error) ||
|
|
||||||
error == 0) {
|
|
||||||
error += bearingCorrection;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
camTicker++;
|
|
||||||
TELE.addData("tx", bearing);
|
|
||||||
TELE.addData("ty", limelightManager.getLatestResult().getTy());
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
camTicker = 0;
|
|
||||||
overrideTurr = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (manualTurret) {
|
|
||||||
pos = turrDefault + (manualOffset / 100);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!overrideTurr) {
|
|
||||||
turretPos = pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpad_right) {
|
|
||||||
manualOffset -= 2;
|
|
||||||
} else if (gamepad2.dpad_left) {
|
|
||||||
manualOffset += 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
//VELOCITY AUTOMATIC
|
|
||||||
|
|
||||||
if (autoVel) {
|
|
||||||
vel = velPrediction(distanceToGoal);
|
|
||||||
} else {
|
|
||||||
vel = manualVel;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.right_stick_button) {
|
|
||||||
autoVel = true;
|
|
||||||
} else if (gamepad2.right_stick_y < -0.5) {
|
|
||||||
autoVel = false;
|
|
||||||
manualVel = 4100;
|
|
||||||
} else if (gamepad2.right_stick_y > 0.5) {
|
|
||||||
autoVel = false;
|
|
||||||
manualVel = 2700;
|
|
||||||
} else if (gamepad2.right_stick_x > 0.5) {
|
|
||||||
autoVel = false;
|
|
||||||
manualVel = 3600;
|
|
||||||
} else if (gamepad2.right_stick_x < -0.5) {
|
|
||||||
autoVel = false;
|
|
||||||
manualVel = 3100;
|
|
||||||
}
|
|
||||||
|
|
||||||
//HOOD:
|
|
||||||
|
|
||||||
if (autoHood) {
|
|
||||||
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
|
||||||
} else {
|
|
||||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadUpWasPressed()) {
|
|
||||||
hoodOffset -= 0.03;
|
|
||||||
autoHoodOffset -= 0.02;
|
|
||||||
|
|
||||||
} else if (gamepad2.dpadDownWasPressed()) {
|
|
||||||
hoodOffset += 0.03;
|
|
||||||
autoHoodOffset += 0.02;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
//TODO: FIX THIS GOOFY THING BECAUSE IT SUCKS @KeshavAnandCode
|
|
||||||
if (gamepad2.left_stick_x > 0.5) {
|
|
||||||
manualTurret = false;
|
|
||||||
} else if (gamepad2.left_stick_x < -0.5) {
|
|
||||||
manualOffset = 0;
|
|
||||||
manualTurret = false;
|
|
||||||
if (gamepad2.left_bumper) {
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(2, 0, 0));
|
|
||||||
sleep(1200);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.left_stick_y < -0.5) {
|
|
||||||
autoHood = true;
|
|
||||||
} else if (gamepad2.left_stick_y > 0.5) {
|
|
||||||
autoHood = false;
|
|
||||||
hoodOffset = 0;
|
|
||||||
if (gamepad2.left_bumper) {
|
|
||||||
xOffset = robotX;
|
|
||||||
yOffset = robotY;
|
|
||||||
headingOffset = robotHeading;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (shootAll) {
|
|
||||||
|
|
||||||
TELE.addData("100% works", shootOrder);
|
|
||||||
|
|
||||||
intake = false;
|
|
||||||
reject = false;
|
|
||||||
|
|
||||||
if (!shootOrder.isEmpty() && (getRuntime() - shootStamp < 12)) {
|
|
||||||
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
|
||||||
boolean shootingDone = false;
|
|
||||||
|
|
||||||
if (!outtake1) {
|
|
||||||
outtake1 = (servo.spinEqual(spindexer_outtakeBall1));
|
|
||||||
}
|
|
||||||
if (!outtake2) {
|
|
||||||
outtake2 = (servo.spinEqual(spindexer_outtakeBall2));
|
|
||||||
}
|
|
||||||
if (!outtake3) {
|
|
||||||
outtake3 = (servo.spinEqual(spindexer_outtakeBall3));
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (currentSlot) {
|
|
||||||
case 1:
|
|
||||||
shootA = shootTeleop(spindexer_outtakeBall1, outtake1, shootStamp2);
|
|
||||||
TELE.addData("shootA", shootA);
|
|
||||||
|
|
||||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
|
||||||
shootingDone = !shootA;
|
|
||||||
} else {
|
|
||||||
shootingDone = true;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
shootB = shootTeleop(spindexer_outtakeBall2, outtake2, shootStamp2);
|
|
||||||
TELE.addData("shootB", shootB);
|
|
||||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
|
||||||
shootingDone = !shootB;
|
|
||||||
} else {
|
|
||||||
shootingDone = true;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case 3:
|
|
||||||
shootC = shootTeleop(spindexer_outtakeBall3, outtake3, shootStamp2);
|
|
||||||
TELE.addData("shootC", shootC);
|
|
||||||
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
|
||||||
shootingDone = !shootC;
|
|
||||||
} else {
|
|
||||||
shootingDone = true;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Remove from the list only if shooting is complete
|
|
||||||
if (shootingDone) {
|
|
||||||
shootOrder.remove(0);
|
|
||||||
shootStamp2 = getRuntime();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
// Finished shooting all balls
|
|
||||||
spindexPos = spindexer_intakePos1;
|
|
||||||
shootA = true;
|
|
||||||
shootB = true;
|
|
||||||
shootC = true;
|
|
||||||
reject = false;
|
|
||||||
intake = true;
|
|
||||||
shootAll = false;
|
|
||||||
outtake1 = false;
|
|
||||||
outtake2 = false;
|
|
||||||
outtake3 = false;
|
|
||||||
|
|
||||||
overrideTurr = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad1.squareWasPressed()) {
|
|
||||||
square = true;
|
|
||||||
shootStamp = getRuntime();
|
|
||||||
shootStamp2 = getRuntime();
|
|
||||||
outtake1 = false;
|
|
||||||
outtake2 = false;
|
|
||||||
outtake3 = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad1.circleWasPressed()) {
|
|
||||||
circle = true;
|
|
||||||
shootStamp = getRuntime();
|
|
||||||
shootStamp2 = getRuntime();
|
|
||||||
|
|
||||||
outtake1 = false;
|
|
||||||
outtake2 = false;
|
|
||||||
outtake3 = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad1.triangleWasPressed()) {
|
|
||||||
triangle = true;
|
|
||||||
shootStamp = getRuntime();
|
|
||||||
shootStamp2 = getRuntime();
|
|
||||||
|
|
||||||
outtake1 = false;
|
|
||||||
outtake2 = false;
|
|
||||||
outtake3 = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (square || circle || triangle) {
|
|
||||||
|
|
||||||
// Count green balls
|
|
||||||
int greenCount = 0;
|
|
||||||
if (green1) greenCount++;
|
|
||||||
if (green2) greenCount++;
|
|
||||||
if (green3) greenCount++;
|
|
||||||
|
|
||||||
// Determine the odd ball color
|
|
||||||
oddBallColor = greenCount < 2; // true = green, false = purple
|
|
||||||
|
|
||||||
shootOrder.clear();
|
|
||||||
|
|
||||||
// Determine shooting order based on button pressed
|
|
||||||
// square = odd ball first, triangle = odd ball second, circle = odd ball third
|
|
||||||
if (square) {
|
|
||||||
// Odd ball first
|
|
||||||
addOddThenRest(shootOrder, oddBallColor);
|
|
||||||
|
|
||||||
} else if (triangle) {
|
|
||||||
// Odd ball second
|
|
||||||
addOddInMiddle(shootOrder, oddBallColor);
|
|
||||||
} else if (circle) {
|
|
||||||
// Odd ball last
|
|
||||||
addOddLast(shootOrder, oddBallColor);
|
|
||||||
}
|
|
||||||
|
|
||||||
circle = false;
|
|
||||||
square = false;
|
|
||||||
triangle = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// Right bumper shoots all balls fastest, ignoring colors
|
|
||||||
if (gamepad1.crossWasPressed()) {
|
|
||||||
shootOrder.clear();
|
|
||||||
shootStamp = getRuntime();
|
|
||||||
|
|
||||||
outtake1 = false;
|
|
||||||
outtake2 = false;
|
|
||||||
outtake3 = false;
|
|
||||||
|
|
||||||
// Fastest order (example: slot 3 → 2 → 1)
|
|
||||||
if (ballIn(3)) {
|
|
||||||
shootOrder.add(3);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ballIn(2)) {
|
|
||||||
shootOrder.add(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ballIn(1)) {
|
|
||||||
shootOrder.add(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!shootOrder.contains(3)) {
|
|
||||||
shootOrder.add(3);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!shootOrder.contains(2)) {
|
|
||||||
shootOrder.add(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!shootOrder.contains(1)) {
|
|
||||||
shootOrder.add(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
shootAll = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
//EXTRA STUFFINESS:
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
for (LynxModule hub : allHubs) {
|
|
||||||
hub.clearBulkCache();
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
|
||||||
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
|
||||||
TELE.addData("Spin3Green", green3 + ": " + ballIn(3));
|
|
||||||
|
|
||||||
TELE.addData("pose", drive.localizer.getPose());
|
|
||||||
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
|
||||||
TELE.addData("distanceToGoal", distanceToGoal);
|
|
||||||
TELE.addData("hood", robot.hood.getPosition());
|
|
||||||
TELE.addData("targetVel", vel);
|
|
||||||
|
|
||||||
TELE.addData("shootOrder", shootOrder);
|
|
||||||
TELE.addData("oddColor", oddBallColor);
|
|
||||||
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// Helper method
|
|
||||||
private boolean checkGreen(List<Boolean> s, List<Double> sT) {
|
|
||||||
if (s.isEmpty()) return false;
|
|
||||||
|
|
||||||
double lastTime = sT.get(sT.size() - 1);
|
|
||||||
int countTrue = 0;
|
|
||||||
int countWindow = 0;
|
|
||||||
|
|
||||||
for (int i = 0; i < s.size(); i++) {
|
|
||||||
if (lastTime - sT.get(i) <= 3.0) { // element is within 2s of last
|
|
||||||
countWindow++;
|
|
||||||
if (s.get(i)) {
|
|
||||||
countTrue++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (countWindow == 0) return false; // avoid divide by zero
|
|
||||||
return countTrue > countWindow / 2.0; // more than 50% true
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
|
||||||
// Set spin positions
|
|
||||||
spindexPos = spindexer;
|
|
||||||
|
|
||||||
// Check if spindexer has reached the target position
|
|
||||||
if (spinOk || getRuntime() - stamp > 1.5) {
|
|
||||||
if (tickerA == 1) {
|
|
||||||
transferStamp = getRuntime();
|
|
||||||
tickerA++;
|
|
||||||
TELE.addLine("tickerSet");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
transferIn = true;
|
|
||||||
TELE.addLine("transferring");
|
|
||||||
|
|
||||||
return true; // still in progress
|
|
||||||
|
|
||||||
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
transferIn = false; // reset for next shot
|
|
||||||
tickerA = 1; // reset ticker
|
|
||||||
transferStamp = 0.0;
|
|
||||||
|
|
||||||
TELE.addLine("shotFinished");
|
|
||||||
|
|
||||||
return false; // finished shooting
|
|
||||||
} else {
|
|
||||||
TELE.addLine("sIP");
|
|
||||||
return true; // still in progress
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
tickerA = 1;
|
|
||||||
transferStamp = getRuntime();
|
|
||||||
transferIn = false;
|
|
||||||
return true; // still moving spin
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public double hoodAnglePrediction(double x) {
|
|
||||||
if (x < 34) {
|
|
||||||
double L = 1.04471;
|
|
||||||
double U = 0.711929;
|
|
||||||
double Q = 120.02263;
|
|
||||||
double B = 0.780982;
|
|
||||||
double M = 20.61191;
|
|
||||||
double v = 10.40506;
|
|
||||||
|
|
||||||
double inner = 1 + Q * Math.exp(-B * (x - M));
|
|
||||||
return L + (U - L) / Math.pow(inner, 1.0 / v);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
// x >= 34
|
|
||||||
return 1.94372 * Math.exp(-0.0528731 * x) + 0.39;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void addOddThenRest(List<Integer> order, boolean oddColor) {
|
|
||||||
// Odd ball first
|
|
||||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
|
||||||
TELE.addData("1", shootOrder);
|
|
||||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
|
||||||
TELE.addData("works", shootOrder);
|
|
||||||
TELE.addData("oddBall", oddColor);
|
|
||||||
shootAll = true;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void addOddInMiddle(List<Integer> order, boolean oddColor) {
|
|
||||||
|
|
||||||
boolean[] used = new boolean[4]; // index 1..3
|
|
||||||
|
|
||||||
// 1) Add a NON-odd ball first
|
|
||||||
for (int i = 1; i <= 3; i++) {
|
|
||||||
if (getBallColor(i) != oddColor) {
|
|
||||||
order.add(i);
|
|
||||||
used[i] = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// 2) Add the odd ball second
|
|
||||||
for (int i = 1; i <= 3; i++) {
|
|
||||||
if (!used[i] && getBallColor(i) == oddColor) {
|
|
||||||
order.add(i);
|
|
||||||
used[i] = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// 3) Add the remaining non-odd ball third
|
|
||||||
for (int i = 1; i <= 3; i++) {
|
|
||||||
if (!used[i] && getBallColor(i) != oddColor) {
|
|
||||||
order.add(i);
|
|
||||||
used[i] = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("works", order);
|
|
||||||
TELE.addData("oddBall", oddColor);
|
|
||||||
shootAll = true;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void addOddLast(List<Integer> order, boolean oddColor) {
|
|
||||||
// Odd ball last
|
|
||||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
|
||||||
TELE.addData("1", shootOrder);
|
|
||||||
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
|
||||||
TELE.addData("works", shootOrder);
|
|
||||||
TELE.addData("oddBall", oddColor);
|
|
||||||
shootAll = true;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns color of ball in slot i (1-based)
|
|
||||||
boolean getBallColor(int slot) {
|
|
||||||
switch (slot) {
|
|
||||||
case 1:
|
|
||||||
return green1;
|
|
||||||
case 2:
|
|
||||||
return green2;
|
|
||||||
case 3:
|
|
||||||
return green3;
|
|
||||||
}
|
|
||||||
return false; // default
|
|
||||||
}
|
|
||||||
|
|
||||||
boolean ballIn(int slot) {
|
|
||||||
List<Double> times =
|
|
||||||
slot == 1 ? s1T :
|
|
||||||
slot == 2 ? s2T :
|
|
||||||
slot == 3 ? s3T : null;
|
|
||||||
|
|
||||||
if (times == null || times.isEmpty()) return false;
|
|
||||||
|
|
||||||
return times.get(times.size() - 1) > getRuntime() - 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
public static double velPrediction(double distance) {
|
|
||||||
if (distance < 30) {
|
|
||||||
return 2750;
|
|
||||||
} else if (distance > 100) {
|
|
||||||
if (distance > 160) {
|
|
||||||
return 4200;
|
|
||||||
}
|
|
||||||
return 3700;
|
|
||||||
} else {
|
|
||||||
// linear interpolation between 40->2650 and 120->3600
|
|
||||||
double slope = (3700.0 - 2750.0) / (100.0 - 30);
|
|
||||||
return (int) Math.round(2750 + slope * (distance - 30));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,55 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
|
||||||
public class ColorTest extends LinearOpMode {
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
while(opModeIsActive()){
|
|
||||||
double green1 = robot.color1.getNormalizedColors().green;
|
|
||||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
|
||||||
double red1 = robot.color1.getNormalizedColors().red;
|
|
||||||
|
|
||||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
|
||||||
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
|
||||||
|
|
||||||
// ----- COLOR 2 -----
|
|
||||||
double green2 = robot.color2.getNormalizedColors().green;
|
|
||||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
|
||||||
double red2 = robot.color2.getNormalizedColors().red;
|
|
||||||
|
|
||||||
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
|
||||||
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
|
||||||
|
|
||||||
// ----- COLOR 3 -----
|
|
||||||
double green3 = robot.color3.getNormalizedColors().green;
|
|
||||||
double blue3 = robot.color3.getNormalizedColors().blue;
|
|
||||||
double red3 = robot.color3.getNormalizedColors().red;
|
|
||||||
|
|
||||||
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
|
||||||
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
|
||||||
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
|
||||||
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,223 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.hardware.lynx.LynxModule;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
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;
|
|
||||||
Servos servo;
|
|
||||||
public boolean green1 = false;
|
|
||||||
public boolean green2 = false;
|
|
||||||
public boolean green3 = false;
|
|
||||||
List<Double> s1G = new ArrayList<>();
|
|
||||||
List<Double> s2G = new ArrayList<>();
|
|
||||||
List<Double> s3G = new ArrayList<>();
|
|
||||||
List<Double> s1T = new ArrayList<>();
|
|
||||||
List<Double> s2T = new ArrayList<>();
|
|
||||||
List<Double> s3T = new ArrayList<>();
|
|
||||||
List<Boolean> s1 = new ArrayList<>();
|
|
||||||
List<Boolean> s2 = new ArrayList<>();
|
|
||||||
List<Boolean> s3 = new ArrayList<>();
|
|
||||||
public static int mode = 0; // 0 for teleop, 1 for auto
|
|
||||||
public static double manualPow = 0.15;
|
|
||||||
double stamp = 0;
|
|
||||||
int ticker = 0;
|
|
||||||
boolean steadySpin = false;
|
|
||||||
double powPID = 0.0;
|
|
||||||
boolean intake = true;
|
|
||||||
double spindexerPos = spindexer_intakePos1;
|
|
||||||
boolean wasMoving = false;
|
|
||||||
double currentPos = 0.0;
|
|
||||||
double initPos = 0.0;
|
|
||||||
boolean reverse = false;
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
|
||||||
for (LynxModule hub : allHubs) {
|
|
||||||
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
|
||||||
}
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
|
||||||
if (mode == 0) {
|
|
||||||
if (gamepad1.right_bumper) {
|
|
||||||
ticker++;
|
|
||||||
if (ticker % 16 == 0){
|
|
||||||
currentPos = servo.getSpinPos();
|
|
||||||
if (Math.abs(currentPos - initPos) == 0.0){
|
|
||||||
reverse = !reverse;
|
|
||||||
}
|
|
||||||
initPos = currentPos;
|
|
||||||
}
|
|
||||||
if (reverse){
|
|
||||||
robot.spin1.setPower(manualPow);
|
|
||||||
robot.spin2.setPower(-manualPow);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPower(-manualPow);
|
|
||||||
robot.spin2.setPower(manualPow);
|
|
||||||
}
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
stamp = getRuntime();
|
|
||||||
TELE.addData("Reverse?", reverse);
|
|
||||||
TELE.update();
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < 1) {
|
|
||||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker = 0;
|
|
||||||
}
|
|
||||||
} else if (mode == 1) {
|
|
||||||
|
|
||||||
if (gamepad1.right_bumper && intake){
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
} else if (gamepad1.left_bumper){
|
|
||||||
robot.intake.setPower(-1);
|
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
colorDetect();
|
|
||||||
spindexer();
|
|
||||||
|
|
||||||
if (ballIn(1) && steadySpin && intake && getRuntime() - stamp > 0.5){
|
|
||||||
if (!ballIn(2)){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
spindexerPos = spindexer_intakePos2;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
spindexerPos = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
spindexerPos = spindexer_intakePos1;
|
|
||||||
}
|
|
||||||
} else if (!ballIn(3)){
|
|
||||||
if (servo.spinEqual(spindexer_intakePos1)){
|
|
||||||
spindexerPos = spindexer_intakePos3;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos2)){
|
|
||||||
spindexerPos = spindexer_intakePos1;
|
|
||||||
} else if (servo.spinEqual(spindexer_intakePos3)){
|
|
||||||
spindexerPos = spindexer_intakePos2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} else if (mode == 2){ // switch to this mode before switching modes or to reset balls
|
|
||||||
powPID = 0;
|
|
||||||
spindexerPos = spindexer_intakePos1;
|
|
||||||
stamp = getRuntime();
|
|
||||||
ticker = 0;
|
|
||||||
spindexer();
|
|
||||||
intake = true;
|
|
||||||
}
|
|
||||||
for (LynxModule hub : allHubs) {
|
|
||||||
hub.clearBulkCache();
|
|
||||||
}
|
|
||||||
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
|
||||||
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
|
||||||
double rx = gamepad1.left_stick_x;
|
|
||||||
|
|
||||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
|
||||||
double frontLeftPower = (y + x + rx) / denominator;
|
|
||||||
double backLeftPower = (y - x + rx) / denominator;
|
|
||||||
double frontRightPower = (y - x - rx) / denominator;
|
|
||||||
double backRightPower = (y + x - rx) / denominator;
|
|
||||||
|
|
||||||
robot.frontLeft.setPower(frontLeftPower);
|
|
||||||
robot.backLeft.setPower(backLeftPower);
|
|
||||||
robot.frontRight.setPower(frontRightPower);
|
|
||||||
robot.backRight.setPower(backRightPower);
|
|
||||||
|
|
||||||
TELE.addData("Manual Power", manualPow);
|
|
||||||
TELE.addData("PID Power", powPID);
|
|
||||||
TELE.addData("B1", ballIn(1));
|
|
||||||
TELE.addData("B2", ballIn(2));
|
|
||||||
TELE.addData("B3", ballIn(3));
|
|
||||||
TELE.addData("Spindex Pos", servo.getSpinPos());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void colorDetect() {
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
TELE.addData("Color 1 Distance", s1D);
|
|
||||||
TELE.addData("Color 2 Distance", s2D);
|
|
||||||
TELE.addData("Color 3 Distance", s3D);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (s1D < 43) {
|
|
||||||
s1T.add(getRuntime());
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s2D < 60) {
|
|
||||||
s2T.add(getRuntime());
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s3D < 33) {
|
|
||||||
s3T.add(getRuntime());
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void spindexer() {
|
|
||||||
boolean atTarget = servo.spinEqual(spindexerPos);
|
|
||||||
|
|
||||||
if (!atTarget) {
|
|
||||||
powPID = servo.setSpinPos(spindexerPos);
|
|
||||||
robot.spin1.setPower(powPID);
|
|
||||||
robot.spin2.setPower(-powPID);
|
|
||||||
|
|
||||||
steadySpin = false;
|
|
||||||
wasMoving = true; // remember we were moving
|
|
||||||
stamp = getRuntime();
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPower(0);
|
|
||||||
robot.spin2.setPower(0);
|
|
||||||
steadySpin = true;
|
|
||||||
wasMoving = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
boolean ballIn(int slot) {
|
|
||||||
List<Double> times;
|
|
||||||
|
|
||||||
if (slot == 1) {times = s1T;}
|
|
||||||
else if (slot == 2) {times = s2T;}
|
|
||||||
else if (slot == 3) {times = s3T;}
|
|
||||||
else return false;
|
|
||||||
|
|
||||||
if (!times.isEmpty()){
|
|
||||||
return times.get(times.size() - 1) > getRuntime() - 2;
|
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,77 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import java.util.List;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@TeleOp
|
|
||||||
//TODO: fix to get the apriltag that it is reading
|
|
||||||
public class LimelightTest extends LinearOpMode {
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
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 mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "Limelight");
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
limelight.pipelineSwitch(pipeline);
|
|
||||||
waitForStart();
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
limelight.start();
|
|
||||||
while (opModeIsActive()){
|
|
||||||
if (mode == 0){
|
|
||||||
limelight.pipelineSwitch(pipeline);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (mode == 1){
|
|
||||||
limelight.pipelineSwitch(1);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null && result.isValid()) {
|
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
|
||||||
int id = fiducial.getFiducialId();
|
|
||||||
TELE.addData("ID", id);
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
} else if (mode == 2){
|
|
||||||
limelight.pipelineSwitch(4);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (mode == 3){
|
|
||||||
limelight.pipelineSwitch(5);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
limelight.pipelineSwitch(0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,74 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
import com.qualcomm.robotcore.hardware.CRServo;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
|
||||||
|
|
||||||
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;
|
|
||||||
|
|
||||||
public static double target = 0.5;
|
|
||||||
|
|
||||||
public static int mode = 0; //0 is for turret, 1 is for spindexer
|
|
||||||
|
|
||||||
public static double scalar = 1.01;
|
|
||||||
public static double restPos = 0.0;
|
|
||||||
|
|
||||||
Robot robot;
|
|
||||||
|
|
||||||
double pos = 0.0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
PIDFController controller = new PIDFController(p, i, d, f);
|
|
||||||
|
|
||||||
controller.setTolerance(0);
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
|
|
||||||
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
|
||||||
controller.setPIDF(p, i, d, f);
|
|
||||||
|
|
||||||
if (mode == 0) {
|
|
||||||
pos = scalar * ((robot.turr1Pos.getVoltage() - restPos) / 3.3);
|
|
||||||
|
|
||||||
double pid = controller.calculate(pos, target);
|
|
||||||
|
|
||||||
robot.turr1.setPower(pid);
|
|
||||||
robot.turr2.setPower(-pid);
|
|
||||||
} else if (mode == 1) {
|
|
||||||
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
|
||||||
|
|
||||||
double pid = controller.calculate(pos, target);
|
|
||||||
|
|
||||||
robot.spin1.setPower(pid);
|
|
||||||
robot.spin2.setPower(-pid);
|
|
||||||
}
|
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
|
||||||
telemetry.addData("Turret Voltage", robot.turr1Pos.getVoltage());
|
|
||||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
|
||||||
telemetry.addData("target", target);
|
|
||||||
telemetry.addData("Mode", mode);
|
|
||||||
telemetry.update();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,7 +1,5 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
@@ -9,7 +7,6 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
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.Robot;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@@ -19,14 +16,18 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
public static int mode = 0;
|
public static int mode = 0;
|
||||||
public static double parameter = 0.0;
|
public static double parameter = 0.0;
|
||||||
// --- CONSTANTS YOU TUNE ---
|
// --- CONSTANTS YOU TUNE ---
|
||||||
|
public static double MAX_RPM = 4500; // your measured max RPM
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
|
||||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||||
public static double transferPower = 1.0;
|
public static double transferPower = 0.0;
|
||||||
public static double hoodPos = 0.501;
|
public static double hoodPos = 0.501;
|
||||||
|
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
public static boolean shoot = false;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
Flywheel flywheel;
|
private double lastEncoderRevolutions = 0.0;
|
||||||
|
private double lastTimeStamp = 0.0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -34,7 +35,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
DcMotorEx leftShooter = robot.shooter1;
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new Flywheel();
|
DcMotorEx encoder = robot.shooter1;
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -46,35 +47,60 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
double kF = 1.0 / MAX_RPM; // baseline feedforward
|
||||||
|
|
||||||
|
double encoderRevolutions = (double) encoder.getCurrentPosition() / 2048;
|
||||||
|
|
||||||
|
double velocity = -60 * (encoderRevolutions - lastEncoderRevolutions) / (getRuntime() - lastTimeStamp);
|
||||||
|
|
||||||
|
TELE.addLine("Mode: 0 = Manual, 1 = Vel, 2 = Pos");
|
||||||
|
TELE.addLine("Parameter = pow, vel, or pos");
|
||||||
|
TELE.addData("leftShooterPower", leftShooter.getPower());
|
||||||
|
TELE.addData("rightShooterPower", rightShooter.getPower());
|
||||||
|
TELE.addData("shaftEncoderPos", encoderRevolutions);
|
||||||
|
TELE.addData("shaftEncoderVel", velocity);
|
||||||
|
|
||||||
|
double velPID;
|
||||||
|
|
||||||
if (mode == 0) {
|
if (mode == 0) {
|
||||||
rightShooter.setPower(parameter);
|
rightShooter.setPower(parameter);
|
||||||
leftShooter.setPower(parameter);
|
leftShooter.setPower(parameter);
|
||||||
} else if (mode == 1) {
|
} else if (mode == 1) {
|
||||||
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition());
|
|
||||||
rightShooter.setPower(powPID);
|
// --- FEEDFORWARD BASE POWER ---
|
||||||
leftShooter.setPower(powPID);
|
double feed = kF * parameter; // Example: vel=2500 → feed=0.5
|
||||||
TELE.addData("PIDPower", powPID);
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = parameter - velocity;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
velPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
velPID = Math.max(0, Math.min(1, velPID));
|
||||||
|
|
||||||
|
rightShooter.setPower(velPID);
|
||||||
|
leftShooter.setPower(velPID);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
lastTimeStamp = getRuntime();
|
||||||
|
lastEncoderRevolutions = (double) encoder.getCurrentPosition() / 2048;
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (turretPos!=0.501){
|
if (turretPos!=0.501){
|
||||||
robot.turr1.setPower(turretPos);
|
robot.turr1.setPosition(turretPos);
|
||||||
robot.turr2.setPower(turretPos);
|
robot.turr2.setPosition(turretPos);
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.transfer.setPower(transferPower);
|
robot.transfer.setPower(transferPower);
|
||||||
if (shoot) {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
}
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Power", robot.shooter1.getPower());
|
|
||||||
TELE.addData("Steady?", flywheel.getSteady());
|
|
||||||
TELE.addData("Position", robot.shooter1.getCurrentPosition());
|
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
|
|||||||
@@ -7,22 +7,21 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|||||||
|
|
||||||
public class Flywheel {
|
public class Flywheel {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
double initPos = 0.0;
|
double initPos = 0.0;
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
double stamp1 = 0.0;
|
double stamp1 = 0.0;
|
||||||
double ticker = 0.0;
|
double ticker = 0.0;
|
||||||
|
double stamp2 = 0.0;
|
||||||
double currentPos = 0.0;
|
double currentPos = 0.0;
|
||||||
|
boolean prevSteady = false;
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
double velo1 = 0.0;
|
double prevVelo = 0.0;
|
||||||
double velo2 = 0.0;
|
|
||||||
double velo3 = 0.0;
|
|
||||||
double velo4 = 0.0;
|
|
||||||
double velo5 = 0.0;
|
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
|
|
||||||
public Flywheel () {
|
public Flywheel () {
|
||||||
//robot = new Robot(hardwareMap);
|
//robot = new Robot(hardwareMap);
|
||||||
}
|
}
|
||||||
@@ -42,22 +41,15 @@ public class Flywheel {
|
|||||||
|
|
||||||
|
|
||||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||||
targetVelocity = commandedVelocity;
|
targetVelocity = (double) commandedVelocity;
|
||||||
|
|
||||||
ticker++;
|
ticker++;
|
||||||
if (ticker % 2 == 0) {
|
if (ticker % 8 == 0) {
|
||||||
velo5 = velo4;
|
|
||||||
velo4 = velo3;
|
|
||||||
velo3 = velo2;
|
|
||||||
velo2 = velo1;
|
|
||||||
|
|
||||||
currentPos = shooter1CurPos / 2048;
|
currentPos = shooter1CurPos / 2048;
|
||||||
stamp = getTimeSeconds(); //getRuntime();
|
stamp = getTimeSeconds(); //getRuntime();
|
||||||
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
initPos = currentPos;
|
initPos = currentPos;
|
||||||
stamp1 = stamp;
|
stamp1 = stamp;
|
||||||
|
|
||||||
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
|
||||||
}
|
}
|
||||||
// Flywheel control code here
|
// Flywheel control code here
|
||||||
if (targetVelocity - velo > 500) {
|
if (targetVelocity - velo > 500) {
|
||||||
@@ -82,12 +74,19 @@ public class Flywheel {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// really should be a running average of the last 5
|
// really should be a running average of the last 5
|
||||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
if ((Math.abs(targetVelocity - velo) < 150.0) && (Math.abs(targetVelocity - prevVelo) < 150.0))
|
||||||
|
{
|
||||||
|
steady = true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
steady = false;
|
||||||
|
}
|
||||||
|
|
||||||
return powPID;
|
return powPID;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void update()
|
public void update()
|
||||||
{
|
{
|
||||||
}
|
};
|
||||||
}
|
};
|
||||||
@@ -1,104 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class FlywheelV2 {
|
|
||||||
public static double kP = 0.001; // small proportional gain (tune this)
|
|
||||||
public static double maxStep = 0.06; // prevents sudden jumps
|
|
||||||
double initPos1 = 0.0;
|
|
||||||
double initPos2 = 0.0;
|
|
||||||
double stamp = 0.0;
|
|
||||||
double stamp1 = 0.0;
|
|
||||||
double ticker = 0.0;
|
|
||||||
double currentPos1 = 0.0;
|
|
||||||
double currentPos2 = 0.0;
|
|
||||||
double velo = 0.0;
|
|
||||||
double velo1 = 0.0;
|
|
||||||
double velo1a = 0.0;
|
|
||||||
double velo1b = 0.0;
|
|
||||||
double velo2 = 0.0;
|
|
||||||
double velo3 = 0.0;
|
|
||||||
double velo4 = 0.0;
|
|
||||||
double velo5 = 0.0;
|
|
||||||
double targetVelocity = 0.0;
|
|
||||||
double powPID = 0.0;
|
|
||||||
boolean steady = false;
|
|
||||||
|
|
||||||
public FlywheelV2() {
|
|
||||||
//robot = new Robot(hardwareMap);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getVelo(double shooter1CurPos, double shooter2CurPos) {
|
|
||||||
ticker++;
|
|
||||||
if (ticker % 2 == 0) {
|
|
||||||
velo5 = velo4;
|
|
||||||
velo4 = velo3;
|
|
||||||
velo3 = velo2;
|
|
||||||
velo2 = velo1;
|
|
||||||
|
|
||||||
currentPos1 = shooter1CurPos / 28;
|
|
||||||
currentPos2 = shooter2CurPos / 28;
|
|
||||||
stamp = getTimeSeconds(); //getRuntime();
|
|
||||||
velo1a = 60 * ((currentPos1 - initPos1) / (stamp - stamp1));
|
|
||||||
velo1b = 60 * ((currentPos2 - initPos2) / (stamp - stamp1));
|
|
||||||
initPos1 = currentPos1;
|
|
||||||
initPos2 = currentPos2;
|
|
||||||
stamp1 = stamp;
|
|
||||||
|
|
||||||
if (velo1a < 200){
|
|
||||||
velo1 = velo1b;
|
|
||||||
} else if (velo1b < 200){
|
|
||||||
velo1 = velo1a;
|
|
||||||
} else {
|
|
||||||
velo1 = (velo1a + velo1b) / 2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return ((velo1 + velo2 + velo3 + velo4 + velo5) / 5);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getVelo1() { return (velo1a + velo2 + velo3 + velo4 + velo5) / 5; }
|
|
||||||
|
|
||||||
public double getVelo2() { return (velo1b + velo2 + velo3 + velo4 + velo5) / 5; }
|
|
||||||
|
|
||||||
public boolean getSteady() {
|
|
||||||
return steady;
|
|
||||||
}
|
|
||||||
|
|
||||||
private double getTimeSeconds() {
|
|
||||||
return (double) System.currentTimeMillis() / 1000.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos, double shooter2CurPos) {
|
|
||||||
targetVelocity = commandedVelocity;
|
|
||||||
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
|
||||||
// Flywheel PID code here
|
|
||||||
if (targetVelocity - velo > 500) {
|
|
||||||
powPID = 1.0;
|
|
||||||
} else if (velo - targetVelocity > 500) {
|
|
||||||
powPID = 0.0;
|
|
||||||
} else {
|
|
||||||
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
|
||||||
|
|
||||||
// --- PROPORTIONAL CORRECTION ---
|
|
||||||
double error = targetVelocity - velo;
|
|
||||||
double correction = kP * error;
|
|
||||||
|
|
||||||
// limit how fast power changes (prevents oscillation)
|
|
||||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
|
||||||
|
|
||||||
// --- FINAL MOTOR POWER ---
|
|
||||||
powPID = feed + correction;
|
|
||||||
|
|
||||||
// clamp to allowed range
|
|
||||||
powPID = Math.max(0, Math.min(1, powPID));
|
|
||||||
}
|
|
||||||
|
|
||||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
|
||||||
|
|
||||||
return powPID;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void update() {
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,103 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
|
|
||||||
import java.util.List;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class LimelightManager {
|
|
||||||
private Limelight3A limelight;
|
|
||||||
private LLResult lastResult;
|
|
||||||
private int lastFiducialId = -1;
|
|
||||||
private double lastBearing = 0.0;
|
|
||||||
|
|
||||||
public static final int PIPELINE_DEFAULT = 1;
|
|
||||||
public static final int PIPELINE_BLUE_DETECTION = 2;
|
|
||||||
public static final int PIPELINE_RED_DETECTION = 3;
|
|
||||||
|
|
||||||
public enum LimelightMode {
|
|
||||||
OBELISK_DETECTION(PIPELINE_DEFAULT),
|
|
||||||
BLUE_GOAL(PIPELINE_BLUE_DETECTION),
|
|
||||||
RED_GOAL(PIPELINE_RED_DETECTION);
|
|
||||||
|
|
||||||
public final int pipeline;
|
|
||||||
|
|
||||||
LimelightMode(int pipeline) {
|
|
||||||
this.pipeline = pipeline;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public LimelightManager(HardwareMap hardwareMap, boolean enabled) {
|
|
||||||
if (enabled) {
|
|
||||||
this.limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void init() {
|
|
||||||
if (limelight != null) {
|
|
||||||
limelight.start();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void switchMode(LimelightMode mode) {
|
|
||||||
if (limelight != null) {
|
|
||||||
limelight.pipelineSwitch(mode.pipeline);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setPipeline(int pipeline) {
|
|
||||||
if (limelight != null) {
|
|
||||||
limelight.pipelineSwitch(pipeline);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public void update() {
|
|
||||||
if (limelight != null) {
|
|
||||||
lastResult = limelight.getLatestResult();
|
|
||||||
if (lastResult != null && lastResult.isValid()) {
|
|
||||||
lastBearing = lastResult.getTx();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getBearing() {
|
|
||||||
return lastBearing;
|
|
||||||
}
|
|
||||||
|
|
||||||
public int detectFiducial() {
|
|
||||||
if (lastResult != null && lastResult.isValid()) {
|
|
||||||
List<LLResultTypes.FiducialResult> fiducials = lastResult.getFiducialResults();
|
|
||||||
if (!fiducials.isEmpty()) {
|
|
||||||
lastFiducialId = fiducials.get(0).getFiducialId();
|
|
||||||
return lastFiducialId;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
public int getLastFiducialId() {
|
|
||||||
return lastFiducialId;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean isFiducialDetected(int id) {
|
|
||||||
return lastFiducialId == id;
|
|
||||||
}
|
|
||||||
|
|
||||||
public LLResult getLatestResult() {
|
|
||||||
return lastResult;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean isConnected() {
|
|
||||||
return limelight != null;
|
|
||||||
}
|
|
||||||
|
|
||||||
public Limelight3A getLimelight() {
|
|
||||||
return limelight;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,7 +1,5 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
@@ -13,47 +11,27 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|||||||
public class PositionalServoProgrammer extends LinearOpMode {
|
public class PositionalServoProgrammer extends LinearOpMode {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Servos servo;
|
|
||||||
|
|
||||||
public static double spindexPos = 0.501;
|
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 turretPos = 0.501;
|
||||||
public static double turretPow = 0.0;
|
|
||||||
public static double turrHoldPow = 0.0;
|
|
||||||
public static double transferPos = 0.501;
|
public static double transferPos = 0.501;
|
||||||
public static double hoodPos = 0.501;
|
public static double hoodPos = 0.501;
|
||||||
public static int mode = 0; //0 for positional, 1 for power
|
|
||||||
|
|
||||||
|
public static double scalar = 1.112;
|
||||||
|
public static double restPos = 0.15;
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
while (opModeIsActive()){
|
while (opModeIsActive()){
|
||||||
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos) && mode == 0){
|
if (spindexPos != 0.501){
|
||||||
double pos = servo.setSpinPos(spindexPos);
|
robot.spin1.setPosition(spindexPos);
|
||||||
robot.spin1.setPower(pos);
|
robot.spin2.setPosition(1-spindexPos);
|
||||||
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 (turretPos != 0.501 && !servo.turretEqual(turretPos)){
|
if (turretPos != 0.501){
|
||||||
double pos = servo.setTurrPos(turretPos);
|
robot.turr1.setPosition(turretPos);
|
||||||
robot.turr1.setPower(pos);
|
robot.turr2.setPosition(1-turretPos);
|
||||||
robot.turr2.setPower(-pos);
|
|
||||||
} else if (mode == 0){
|
|
||||||
robot.turr1.setPower(turrHoldPow);
|
|
||||||
robot.turr2.setPower(turrHoldPow);
|
|
||||||
} else {
|
|
||||||
robot.turr1.setPower(turretPow);
|
|
||||||
robot.turr2.setPower(-turretPow);
|
|
||||||
}
|
}
|
||||||
if (transferPos != 0.501){
|
if (transferPos != 0.501){
|
||||||
robot.transferServo.setPosition(transferPos);
|
robot.transferServo.setPosition(transferPos);
|
||||||
@@ -61,13 +39,14 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
if (hoodPos != 0.501){
|
if (hoodPos != 0.501){
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos);
|
||||||
}
|
}
|
||||||
TELE.addData("spindexer", servo.getSpinPos());
|
TELE.addData("spindexer", scalar*((robot.spin1Pos.getVoltage() - restPos) / 3.3));
|
||||||
TELE.addData("turret", servo.getTurrPos());
|
TELE.addData("hood", 1-scalar*((robot.hoodPos.getVoltage() - restPos) / 3.3));
|
||||||
TELE.addData("spindexer voltage", robot.spin1Pos.getVoltage());
|
TELE.addData("transferServo", scalar*((robot.transferServoPos.getVoltage() - restPos) / 3.3));
|
||||||
TELE.addData("hood voltage", robot.hoodPos.getVoltage());
|
TELE.addData("turret", scalar*((robot.turr1Pos.getVoltage() - restPos) / 3.3));
|
||||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
TELE.addData("spindexerA", robot.spin1Pos.getVoltage());
|
||||||
TELE.addData("turret voltage", robot.turr1Pos.getVoltage());
|
TELE.addData("hoodA", robot.hoodPos.getVoltage());
|
||||||
TELE.addData("Spin Equal", servo.spinEqual(spindexPos));
|
TELE.addData("transferServoA", robot.transferServoPos.getVoltage());
|
||||||
|
TELE.addData("turretA", robot.turr1Pos.getVoltage());
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,9 +1,7 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||||
import com.qualcomm.robotcore.hardware.CRServo;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
@@ -20,42 +18,67 @@ public class Robot {
|
|||||||
|
|
||||||
public DcMotorEx frontLeft;
|
public DcMotorEx frontLeft;
|
||||||
public DcMotorEx frontRight;
|
public DcMotorEx frontRight;
|
||||||
|
|
||||||
public DcMotorEx backLeft;
|
public DcMotorEx backLeft;
|
||||||
|
|
||||||
public DcMotorEx backRight;
|
public DcMotorEx backRight;
|
||||||
|
|
||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
|
|
||||||
public DcMotorEx transfer;
|
public DcMotorEx transfer;
|
||||||
|
|
||||||
public DcMotorEx shooter1;
|
public DcMotorEx shooter1;
|
||||||
public DcMotorEx shooter2;
|
public DcMotorEx shooter2;
|
||||||
public Servo hood;
|
public Servo hood;
|
||||||
|
|
||||||
public Servo transferServo;
|
public Servo transferServo;
|
||||||
|
|
||||||
public Servo rejecter;
|
public Servo rejecter;
|
||||||
public CRServo turr1;
|
|
||||||
public CRServo turr2;
|
public Servo turr1;
|
||||||
public CRServo spin1;
|
|
||||||
public CRServo spin2;
|
public Servo turr2;
|
||||||
|
|
||||||
|
public Servo spin1;
|
||||||
|
|
||||||
|
public Servo spin2;
|
||||||
|
|
||||||
public DigitalChannel pin0;
|
public DigitalChannel pin0;
|
||||||
|
|
||||||
public DigitalChannel pin1;
|
public DigitalChannel pin1;
|
||||||
public DigitalChannel pin2;
|
public DigitalChannel pin2;
|
||||||
public DigitalChannel pin3;
|
public DigitalChannel pin3;
|
||||||
public DigitalChannel pin4;
|
public DigitalChannel pin4;
|
||||||
public DigitalChannel pin5;
|
|
||||||
public AnalogInput analogInput;
|
|
||||||
public AnalogInput analogInput2;
|
|
||||||
public AnalogInput spin1Pos;
|
|
||||||
public AnalogInput spin2Pos;
|
|
||||||
public AnalogInput hoodPos;
|
|
||||||
public AnalogInput turr1Pos;
|
|
||||||
public AnalogInput turr2Pos;
|
|
||||||
public AnalogInput transferServoPos;
|
|
||||||
public AprilTagProcessor aprilTagProcessor;
|
|
||||||
public WebcamName webcam;
|
|
||||||
public DcMotorEx shooterEncoder;
|
|
||||||
public RevColorSensorV3 color1;
|
|
||||||
public RevColorSensorV3 color2;
|
|
||||||
public RevColorSensorV3 color3;
|
|
||||||
public Limelight3A limelight;
|
|
||||||
|
|
||||||
public static boolean usingLimelight = true;
|
public DigitalChannel pin5;
|
||||||
|
|
||||||
|
public AnalogInput analogInput;
|
||||||
|
|
||||||
|
public AnalogInput analogInput2;
|
||||||
|
|
||||||
|
public AnalogInput spin1Pos;
|
||||||
|
|
||||||
|
public AnalogInput spin2Pos;
|
||||||
|
|
||||||
|
public AnalogInput hoodPos;
|
||||||
|
|
||||||
|
public AnalogInput turr1Pos;
|
||||||
|
|
||||||
|
public AnalogInput turr2Pos;
|
||||||
|
|
||||||
|
public AnalogInput transferServoPos;
|
||||||
|
|
||||||
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
|
|
||||||
|
public WebcamName webcam;
|
||||||
|
|
||||||
|
public DcMotorEx shooterEncoder;
|
||||||
|
|
||||||
|
public RevColorSensorV3 color1;
|
||||||
|
|
||||||
|
public RevColorSensorV3 color2;
|
||||||
|
|
||||||
|
public RevColorSensorV3 color3;
|
||||||
|
|
||||||
public Robot(HardwareMap hardwareMap) {
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
@@ -81,8 +104,6 @@ public class Robot {
|
|||||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||||
|
|
||||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
|
||||||
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
|
||||||
|
|
||||||
shooterEncoder = shooter1;
|
shooterEncoder = shooter1;
|
||||||
|
|
||||||
@@ -90,25 +111,22 @@ public class Robot {
|
|||||||
|
|
||||||
hoodPos = hardwareMap.get(AnalogInput.class, "hoodPos");
|
hoodPos = hardwareMap.get(AnalogInput.class, "hoodPos");
|
||||||
|
|
||||||
turr1 = hardwareMap.get(CRServo.class, "t1");
|
turr1 = hardwareMap.get(Servo.class, "t1");
|
||||||
|
|
||||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos");
|
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos");
|
||||||
|
|
||||||
turr2 = hardwareMap.get(CRServo.class, "t2");
|
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||||
|
|
||||||
turr2Pos = hardwareMap.get(AnalogInput.class, "t2Pos");
|
turr2Pos = hardwareMap.get(AnalogInput.class, "t2Pos");
|
||||||
|
|
||||||
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
spin1 = hardwareMap.get(Servo.class, "spin1");
|
||||||
|
|
||||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
spin2 = hardwareMap.get(Servo.class, "spin2");
|
||||||
|
|
||||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||||
|
|
||||||
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
|
|
||||||
pin0 = hardwareMap.get(DigitalChannel.class, "pin0");
|
pin0 = hardwareMap.get(DigitalChannel.class, "pin0");
|
||||||
|
|
||||||
pin1 = hardwareMap.get(DigitalChannel.class, "pin1");
|
pin1 = hardwareMap.get(DigitalChannel.class, "pin1");
|
||||||
@@ -142,9 +160,5 @@ public class Robot {
|
|||||||
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
|
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
|
||||||
|
|
||||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||||
|
|
||||||
if (usingLimelight){
|
|
||||||
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,60 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Servos {
|
|
||||||
Robot robot;
|
|
||||||
|
|
||||||
PIDFController spinPID;
|
|
||||||
|
|
||||||
PIDFController turretPID;
|
|
||||||
|
|
||||||
//PID constants
|
|
||||||
// TODO: get PIDF constants
|
|
||||||
public static double spinP = 3.4, spinI = 0, spinD = 0.075, spinF = 0.02;
|
|
||||||
public static double turrP = 4.0, turrI = 0.0, turrD = 0.0, turrF = 0.0;
|
|
||||||
|
|
||||||
public static double spin_scalar = 1.0086;
|
|
||||||
public static double spin_restPos = 0.0;
|
|
||||||
public static double turret_scalar = 1.009;
|
|
||||||
public static double turret_restPos = 0.0;
|
|
||||||
|
|
||||||
public Servos(HardwareMap hardwareMap) {
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
|
||||||
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
|
||||||
}
|
|
||||||
|
|
||||||
// In the code below, encoder = robot.servo.getVoltage()
|
|
||||||
|
|
||||||
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);
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
|
||||||
return Math.abs(pos - this.getSpinPos()) < 0.02;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getTurrPos() {
|
|
||||||
return turret_scalar * ((robot.turr1Pos.getVoltage() - turret_restPos) / 3.3);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
|
||||||
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
|
||||||
|
|
||||||
return spinPID.calculate(this.getTurrPos(), pos);
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
|
||||||
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Reference in New Issue
Block a user