65 Commits

Author SHA1 Message Date
8840205fb3 Fully Merged Presumably 2026-01-29 15:25:12 -06:00
6b71bb17f4 Merge branch 'auto9Ball'
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Auto_LT_12Ball.java
2026-01-29 15:21:33 -06:00
f8369b51ed working teleop in progress 2026-01-29 15:20:02 -06:00
6c6ea03cac For Daniel to update Poses 2026-01-29 15:11:09 -06:00
c1dda240d3 stash 2026-01-29 14:19:01 -06:00
68e4fdb14d stash 2026-01-29 13:58:27 -06:00
abhiram vishnubhotla
66c5de1b26 Update Spindexer.java 2026-01-29 11:09:55 -06:00
3f4fee0e24 Add functions to get the ball color to spindexer. Attempt to make shoot all in teleop work better. 2026-01-29 09:25:39 -06:00
53290a5982 working auto 2026-01-28 20:22:25 -06:00
7ae7574703 Merge branch 'SpindexerUpgradesInWork' into auto9Ball
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/ServoPositions.java
#	build.dependencies.gradle
2026-01-28 19:43:20 -06:00
66bb5c747f before merge 2026-01-28 19:42:08 -06:00
661730ef18 stash 2026-01-28 19:31:52 -06:00
159b130b5f Integrate shootAll on the Robot. This version was working except with 1 ball. 2026-01-28 17:33:37 -06:00
8bc0b1043a NOT WORKING indexed auto WIP 2026-01-28 17:27:26 -06:00
7a50aa5065 unindexed works-ish jhust some static variables and stuff ig 2026-01-28 16:18:36 -06:00
641d947ec6 last edit 2026-01-28 15:36:44 -06:00
5d0a569f82 spindex progress: not good 2026-01-28 15:23:17 -06:00
f767e82e31 changed servo positions 2026-01-28 13:38:04 -06:00
d088fba20a Create shootAll state machine in spindexer and call from TeleOpV3. Experiment with averaging tiles in Targeting, which is permanently disabled at the moment. 2026-01-28 13:06:53 -06:00
2a45eee878 Update spindexer positions after repair. 2026-01-28 00:45:21 -06:00
486bde729d Wip 2026-01-27 19:28:55 -06:00
a6fe8c14e6 @Matt please take a look at this code 2026-01-27 18:51:24 -06:00
2fd87c9093 @Matt please take a look at this code 2026-01-27 18:38:41 -06:00
80f095cd57 Fixed some stuff presumably..untested 2026-01-27 17:47:25 -06:00
1715fa96cb updated dash version 2026-01-27 16:44:55 -06:00
dea9a10b08 added targeting information and unjaming code (both untested) 2026-01-27 16:36:46 -06:00
0549902505 a lot of changes happened in a galaxy far far away 2026-01-27 15:54:08 -06:00
cfb51cfa15 pipeline fixes 2026-01-27 13:21:51 -06:00
04372ec410 Add a PID to Limelight tracking bringing in track function from Abyss. Simplify spindexer due to errors with advanced code. Start adding Interpolation to Targeting (commented out for now). 2026-01-27 00:58:15 -06:00
e665ddf032 For Daniel 2026-01-26 16:50:47 -06:00
b08fe5ada5 stash 2026-01-26 16:19:44 -06:00
d1434fbaa8 Add Targeting values from shootertesting. Tune flywheel with shootertest. Add additional telemetry. 2026-01-26 01:00:03 -06:00
d216ce78fc Improve Spindexer shaking. Upgrade shooterTest to control the spindexer and fix flywheel real time pidf coef updates.. 2026-01-25 16:48:27 -06:00
8dc03adfd3 Merge with LimelightTesting. 2026-01-25 11:39:26 -06:00
7ffc51f60a Add shoot all ball order 2026-01-25 11:33:56 -06:00
7625f9a640 stash 2026-01-24 17:53:02 -06:00
fefeeb1f2e i need you @KeshavAnandCode 2026-01-24 17:18:57 -06:00
b5a31afe52 i need you @KeshavAnandCode 2026-01-24 15:42:32 -06:00
8d29a80696 need to add zero code to properly test 2026-01-24 14:45:35 -06:00
5922f4e935 need to add zero code to properly test 2026-01-23 22:50:33 -06:00
78d38481a7 stash 2026-01-23 21:44:29 -06:00
8a4bfecbf8 turret 2026-01-23 21:24:38 -06:00
3591e20001 Merge branch 'Targeting' 2026-01-23 20:24:16 -06:00
4050a354f7 Update TelopV3 and Targeting for merge conflicts. 2026-01-23 20:19:21 -06:00
16ffdd003f stash 2026-01-23 19:38:47 -06:00
f20e640c62 Merge remote-tracking branch 'origin/master' into Targeting
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/TurretTest.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java
2026-01-22 22:13:07 -06:00
c2e9d8fa87 Merge remote-tracking branch 'origin/Targeting' into Targeting 2026-01-22 22:00:41 -06:00
46a5366a4a Add Auto ball detect on startup to spindexer to detect how many balls are already in spindexer on power on. 2026-01-22 21:59:58 -06:00
fbdeb6e291 Turret works y8ippee horray hurrah ig 2026-01-22 21:04:25 -06:00
abhiram vishnubhotla
298b7bca8c Merge pull request #13 from Technical-Turbulence-FTC/feature/interpolation
Feature/interpolation
2026-01-22 20:21:05 -06:00
2f0fcad128 updated interpolation in teleop 2026-01-22 20:06:08 -06:00
45199b952b added interpolation 2026-01-22 20:03:00 -06:00
76ceb91fb7 Merge branch 'Targeting' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into turret-refactor-updates 2026-01-22 19:28:42 -06:00
daccec4fdd Add Targeting Class with initial values that still need tuning. Connect Targeting Class to TeleOpV3. Clean up unused code in Flywheel class. 2026-01-22 00:00:17 -06:00
b55d44ae97 Merge branch 'Targeting' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into turret-refactor-updates 2026-01-21 20:01:22 -06:00
50212015e3 trackGoal expected robot centric view, but was fed a field centric view. simple trig to use a deltaPos instead of just pos 2026-01-21 19:04:30 -06:00
c271c88e45 Merge branch 'master' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into test/continuous_ll_track 2026-01-21 18:36:06 -06:00
33300876ef Merge remote-tracking branch 'origin/master' into Targeting 2026-01-21 09:28:59 -06:00
e1745500cc Create new targeting class. Fix Flywheel Error with motor2 velocity and include spindexer pos updates. 2026-01-21 09:28:21 -06:00
0dbf155608 stash 2026-01-20 21:18:42 -06:00
313eeeaa95 Merge remote-tracking branch 'origin/SpindexerPosUpdate' 2026-01-20 20:59:56 -06:00
b28647373a no errors 2026-01-20 20:57:14 -06:00
7e7254aaea turret refaftoring 2026-01-20 20:52:23 -06:00
a3068cea2e Merge branch 'SpindexerRefactor' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into test/continuous_ll_track 2026-01-20 19:17:16 -06:00
f1d4bb9d24 continous ll tracking, TEST 2026-01-19 10:38:34 -06:00
31 changed files with 3479 additions and 707 deletions

View File

@@ -0,0 +1,921 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootH;
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootX;
import static org.firstinspires.ftc.teamcode.constants.Poses.bShootY;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bhPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx1;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.bx4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.bxPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.by1;
import static org.firstinspires.ftc.teamcode.constants.Poses.by2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.by2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.by3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.by3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.by4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.by4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.byPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootH;
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootX;
import static org.firstinspires.ftc.teamcode.constants.Poses.rShootY;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh1;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rh4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rhPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx1;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.rx4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.rxPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry1;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2a;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry2b;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3a;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry3b;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4a;
import static org.firstinspires.ftc.teamcode.constants.Poses.ry4b;
import static org.firstinspires.ftc.teamcode.constants.Poses.ryPrep;
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.ParallelAction;
import com.acmerobotics.roadrunner.Pose2d;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Poses_V2;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.utils.Flywheel;
import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos;
import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close_12Ball extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2;
public static double shoot0SpinSpeedIncrease = 0.014;
public static double spindexerSpeedIncrease = 0.02;
public static double obeliskTurrPos = 0.53;
public static double normalIntakeTime = 3.0;
public static double shoot1Turr = 0.57;
public static double shoot0XTolerance = 1.0;
public static double turretShootPos = 0.53;
public static double shootAllTime = 1.8;
public static double shoot0Time = 1.6;
public static double intake1Time = 3.0;
public static double flywheel0Time = 3.5;
public static double pickup1Speed = 25;
// ---- SECOND SHOT / PICKUP ----
public static double shoot1Vel = 2300;
public static double shoot1Hood = 0.93;
public static double shootAllVelocity = 2500;
public static double shootAllHood = 0.78;
// ---- PICKUP TIMING ----
public static double pickup1Time = 3.0;
// ---- PICKUP POSITION TOLERANCES ----
public static double pickup1XTolerance = 2.0;
public static double pickup1YTolerance = 2.0;
// ---- OBELISK DETECTION ----
public static double obelisk1Time = 1.5;
public static double obelisk1XTolerance = 2.0;
public static double obelisk1YTolerance = 2.0;
public static double shoot1ToleranceX = 2.0;
public static double shoot1ToleranceY = 2.0;
public static double shoot1Time = 2.0;
public static double shootCycleTime = 2.5;
public int motif = 0;
Robot robot;
MultipleTelemetry TELE;
MecanumDrive drive;
Servos servos;
Spindexer spindexer;
Flywheel flywheel;
Turret turret;
Targeting targeting;
Targeting.Settings targetingSettings;
private double x1, y1, h1;
private double x2a, y2a, h2a, t2a;
private double x2b, y2b, h2b, t2b;
private double x2c, y2c, h2c, t2c;
private double x3a, y3a, h3a;
private double x3b, y3b, h3b;
private double x4a, y4a, h4a;
private double x4b, y4b, h4b;
private double xShoot, yShoot, hShoot;
private double xGate, yGate, hGate;
private double xPrep, yPrep, hPrep;
private double shoot1Tangent;
public Action prepareShootAll(double time) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
robot.transferServo.setPosition(transferServo_out);
turret.manualSetTurret(turretShootPos);
robot.intake.setPower(-((System.currentTimeMillis() - stamp)) / 1000);
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return (System.currentTimeMillis() - stamp) < (time * 1000);
}
};
}
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
return new Action() {
int ticker = 1;
double stamp = 0.0;
double velo = vel;
int shooterTicker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
flywheel.manageFlywheel(vel);
velo = flywheel.getVelo();
drive.updatePoseEstimate();
Poses_V2.teleStart = drive.localizer.getPose();
robot.intake.setPower(-0.3);
if (ticker == 1) {
stamp = getRuntime();
}
ticker++;
robot.intake.setPower(0);
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
if (getRuntime() - stamp < shootTime) {
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
} else {
robot.transferServo.setPosition(transferServo_in);
shooterTicker++;
double prevSpinPos = robot.spin1.getPosition();
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
}
return true;
} else {
robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
spindexer.resetSpindexer();
spindexer.processIntake();
return false;
}
}
};
}
public Action shootAllAuto(double shootTime, double spindexSpeed) {
return new Action() {
int ticker = 1;
double stamp = 0.0;
double velo = 0.0;
int shooterTicker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
velo = flywheel.getVelo();
drive.updatePoseEstimate();
Poses_V2.teleStart = drive.localizer.getPose();
robot.intake.setPower(-0.3);
if (ticker == 1) {
stamp = getRuntime();
}
ticker++;
robot.intake.setPower(0);
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
if (getRuntime() - stamp < shootTime) {
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
} else {
robot.transferServo.setPosition(transferServo_in);
shooterTicker++;
double prevSpinPos = robot.spin1.getPosition();
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
}
return true;
} else {
robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
spindexer.resetSpindexer();
spindexer.processIntake();
return false;
}
}
};
}
public Action intake(double intakeTime) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
spindexer.processIntake();
robot.intake.setPower(1);
motif = turret.detectObelisk();
spindexer.ballCounterLight();
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return (System.currentTimeMillis() - stamp) < (intakeTime * 1000);
}
};
}
public Action detectObelisk(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance,
double turrPos
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
motif = turret.detectObelisk();
robot.turr1.setPosition(turrPos);
robot.turr2.setPosition(1 - turrPos);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return !shouldFinish;
}
};
}
public Action manageFlywheel(
double vel,
double hoodPos,
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
flywheel.manageFlywheel(vel);
robot.hood.setPosition(hoodPos);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return !shouldFinish;
}
};
}
public Action manageShooterAuto(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
double robotX = drive.localizer.getPose().position.x;
double robotY = drive.localizer.getPose().position.y;
double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -15;
double goalY = 0;
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
targetingSettings = targeting.calculateSettings
(robotX, robotY, robotHeading, 0.0, false);
turret.trackGoal(deltaPose);
robot.hood.setPosition(targetingSettings.hoodAngle);
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return !shouldFinish;
}
};
}
public Action manageFlywheelAuto(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
double robotX = drive.localizer.getPose().position.x;
double robotY = drive.localizer.getPose().position.y;
double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -15;
double goalY = 0;
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
targetingSettings = targeting.calculateSettings
(robotX, robotY, robotHeading, 0.0, false);
robot.hood.setPosition(targetingSettings.hoodAngle);
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Hood", robot.hood.getPosition());
TELE.update();
return !shouldFinish;
}
};
}
@Override
public void runOpMode() throws InterruptedException {
robot = new Robot(hardwareMap);
TELE = new MultipleTelemetry(
telemetry, FtcDashboard.getInstance().getTelemetry()
);
flywheel = new Flywheel(hardwareMap);
targeting = new Targeting();
targetingSettings = new Targeting.Settings(0.0, 0.0);
spindexer = new Spindexer(hardwareMap);
servos = new Servos(hardwareMap);
robot.limelight.pipelineSwitch(1);
turret = new Turret(robot, TELE, robot.limelight);
turret.manualSetTurret(0.4);
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
robot.transferServo.setPosition(transferServo_out);
TrajectoryActionBuilder shoot0 = null;
TrajectoryActionBuilder pickup1 = null;
TrajectoryActionBuilder shoot1 = null;
TrajectoryActionBuilder pickup2 = null;
TrajectoryActionBuilder shoot2 = null;
TrajectoryActionBuilder pickup3 = null;
TrajectoryActionBuilder shoot3 = null;
robot.limelight.start();
robot.light.setPosition(1);
while (opModeInInit()) {
robot.hood.setPosition(shoot0Hood);
if (gamepad2.crossWasPressed()) {
redAlliance = !redAlliance;
}
if (redAlliance) {
robot.light.setPosition(0.28);
// ---- FIRST SHOT ----
x1 = rx1;
y1 = ry1;
h1 = rh1;
// ---- PICKUP PATH ----
x2a = rx2a;
y2a = ry2a;
h2a = rh2a;
x2b = rx2b;
y2b = ry2b;
h2b = rh2b;
x3a = rx3a;
y3a = ry3a;
h3a = rh3a;
x3b = rx3b;
y3b = ry3b;
h3b = rh3b;
x4a = rx4a;
y4a = ry4a;
h4a = rh4a;
x4b = rx4b;
y4b = ry4b;
h4b = rh4b;
xPrep = rxPrep;
yPrep = ryPrep;
hPrep = rhPrep;
xShoot = rShootX;
yShoot = rShootY;
hShoot = rShootH;
} else {
robot.light.setPosition(0.6);
// ---- FIRST SHOT ----
x1 = bx1;
y1 = by1;
h1 = bh1;
// ---- PICKUP PATH ----
x2a = bx2a;
y2a = by2a;
h2a = bh2a;
x2b = bx2b;
y2b = by2b;
h2b = bh2b;
x3a = bx3a;
y3a = by3a;
h3a = bh3a;
x3b = bx3b;
y3b = by3b;
h3b = bh3b;
x4a = bx4a;
y4a = by4a;
h4a = bh4a;
x4b = bx4b;
y4b = by4b;
h4b = bh4b;
xPrep = bxPrep;
yPrep = byPrep;
hPrep = bhPrep;
xShoot = bShootX;
yShoot = bShootY;
hShoot = bShootH;
}
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
new TranslationalVelConstraint(pickup1Speed));
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
pickup2 = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
.strafeToLinearHeading(new Vector2d(x3a, y3a), h3a)
.strafeToLinearHeading(new Vector2d(x3b, y3b), h3b,
new TranslationalVelConstraint(pickup1Speed));
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, h3b))
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
pickup3 = drive.actionBuilder(new Pose2d(x1, y1, h1))
.strafeToLinearHeading(new Vector2d(x4a, y4a), h4a)
.strafeToLinearHeading(new Vector2d(x4b, y4b), h4b,
new TranslationalVelConstraint(pickup1Speed));
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, h4b))
.strafeToLinearHeading(new Vector2d(xPrep, yPrep), hPrep)
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
TELE.addData("Red?", redAlliance);
TELE.update();
}
waitForStart();
if (isStopRequested()) return;
if (opModeIsActive()) {
robot.transfer.setPower(1);
assert shoot0 != null;
Actions.runBlocking(
new ParallelAction(
shoot0.build(),
manageFlywheel(
shoot0Vel,
shoot0Hood,
flywheel0Time,
x1,
0.501,
shoot0XTolerance,
0.501
)
)
);
Actions.runBlocking(
shootAll((int) shoot0Vel, shoot0Time, shoot0SpinSpeedIncrease)
);
Actions.runBlocking(
new ParallelAction(
pickup1.build(),
manageFlywheel(
shootAllVelocity,
shootAllHood,
pickup1Time,
x2b,
y2b,
pickup1XTolerance,
pickup1YTolerance
),
intake(intake1Time)
)
);
Actions.runBlocking(
new ParallelAction(
manageFlywheel(
shootAllVelocity,
shootAllHood,
shoot1Time,
0.501,
0.501,
0.501,
0.501
),
shoot1.build(),
prepareShootAll(shoot1Time)
)
);
Actions.runBlocking(
new ParallelAction(
manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501
),
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
Actions.runBlocking(
new ParallelAction(
pickup2.build(),
manageShooterAuto(
normalIntakeTime,
x2b,
y2b,
pickup1XTolerance,
pickup1YTolerance
),
intake(normalIntakeTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageFlywheelAuto(
shootCycleTime,
0.501,
0.501,
0.501,
0.501
),
shoot2.build(),
prepareShootAll(shootCycleTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501
),
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
Actions.runBlocking(
new ParallelAction(
pickup3.build(),
manageShooterAuto(
normalIntakeTime,
x2b,
y2b,
pickup1XTolerance,
pickup1YTolerance
),
intake(normalIntakeTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageFlywheelAuto(
shootCycleTime,
0.501,
0.501,
0.501,
0.501
),
shoot3.build(),
prepareShootAll(shootCycleTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501
),
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
TELE.addLine("finished");
TELE.update();
sleep(2000);
}
}
}

View File

@@ -0,0 +1,804 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bHGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShoot1Tangent;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootH;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootX;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bShootY;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bXGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bYGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bh2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bt2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.bx2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.by2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rHGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShoot1Tangent;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootH;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootX;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rShootY;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rXGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rYGate;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rh2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rt2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.rx2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry1;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2a;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2b;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.ry2c;
import static org.firstinspires.ftc.teamcode.constants.Poses_V2.teleStart;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.ParallelAction;
import com.acmerobotics.roadrunner.Pose2d;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.Servo;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.utils.Flywheel;
import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos;
import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Autonomous(preselectTeleOp = "TeleopV3")
@Config
public class Auto_LT_Close_GateCycle extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2;
public static double shoot0SpinSpeedIncrease = 0.014;
public static double spindexerSpeedIncrease = 0.02;
public static double obeliskTurrPos = 0.53;
public static double gatePickupTime = 3.0;
public static double shoot1Turr = 0.57;
public static double shoot0XTolerance = 1.0;
public static double turretShootPos = 0.72;
public static double shootAllTime = 1.8;
public static double shoot0Time = 1.6;
public static double intake1Time = 3.0;
public static double flywheel0Time = 3.5;
public static double pickup1Speed = 80.0;
// ---- SECOND SHOT / PICKUP ----
public static double shoot1Vel = 2300;
public static double shoot1Hood = 0.93;
public static double shootAllVelocity = 2500;
public static double shootAllHood = 0.78;
// ---- PICKUP TIMING ----
public static double pickup1Time = 3.0;
// ---- PICKUP POSITION TOLERANCES ----
public static double pickup1XTolerance = 2.0;
public static double pickup1YTolerance = 2.0;
// ---- OBELISK DETECTION ----
public static double obelisk1Time = 1.5;
public static double obelisk1XTolerance = 2.0;
public static double obelisk1YTolerance = 2.0;
public static double shoot1ToleranceX = 2.0;
public static double shoot1ToleranceY = 2.0;
public static double shoot1Time = 2.0;
public static double shootCycleTime = 2.5;
public int motif = 0;
Robot robot;
MultipleTelemetry TELE;
MecanumDrive drive;
Servos servos;
Spindexer spindexer;
Flywheel flywheel;
Turret turret;
Targeting targeting;
Targeting.Settings targetingSettings;
private double x1, y1, h1;
private double x2a, y2a, h2a, t2a;
private double x2b, y2b, h2b, t2b;
private double x2c, y2c, h2c, t2c;
private double xShoot, yShoot, hShoot;
private double xGate, yGate, hGate;
private double shoot1Tangent;
public Action prepareShootAll(double time) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
robot.transferServo.setPosition(transferServo_out);
turret.manualSetTurret(turretShootPos);
robot.intake.setPower(-((System.currentTimeMillis() - stamp)) / 1000);
return (System.currentTimeMillis() - stamp) < (time * 1000);
}
};
}
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
return new Action() {
int ticker = 1;
double stamp = 0.0;
double velo = vel;
int shooterTicker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
TELE.addData("Velocity", velo);
TELE.addLine("shooting");
TELE.update();
flywheel.manageFlywheel(vel);
velo = flywheel.getVelo();
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
robot.intake.setPower(-0.3);
if (ticker == 1) {
stamp = getRuntime();
}
ticker++;
robot.intake.setPower(0);
if (getRuntime() - stamp < shootTime) {
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
} else {
robot.transferServo.setPosition(transferServo_in);
shooterTicker++;
double prevSpinPos = robot.spin1.getPosition();
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
}
return true;
} else {
robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
spindexer.resetSpindexer();
spindexer.processIntake();
return false;
}
}
};
}
public Action shootAllAuto(double shootTime, double spindexSpeed) {
return new Action() {
int ticker = 1;
double stamp = 0.0;
double velo = 0.0;
int shooterTicker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
TELE.addData("Velocity", velo);
TELE.addLine("shooting");
TELE.update();
velo = flywheel.getVelo();
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
robot.intake.setPower(-0.3);
if (ticker == 1) {
stamp = getRuntime();
}
ticker++;
robot.intake.setPower(0);
if (getRuntime() - stamp < shootTime) {
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
} else {
robot.transferServo.setPosition(transferServo_in);
shooterTicker++;
double prevSpinPos = robot.spin1.getPosition();
robot.spin1.setPosition(prevSpinPos + spindexSpeed);
robot.spin2.setPosition(1 - prevSpinPos - spindexSpeed);
}
return true;
} else {
robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
spindexer.resetSpindexer();
spindexer.processIntake();
return false;
}
}
};
}
public Action intake(double intakeTime) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
spindexer.processIntake();
robot.intake.setPower(1);
motif = turret.detectObelisk();
spindexer.ballCounterLight();
return (System.currentTimeMillis() - stamp) < (intakeTime * 1000);
}
};
}
public Action detectObelisk(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance,
double turrPos
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
motif = turret.detectObelisk();
robot.turr1.setPosition(turrPos);
robot.turr2.setPosition(1 - turrPos);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
return !shouldFinish;
}
};
}
public Action manageFlywheel(
double vel,
double hoodPos,
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
flywheel.manageFlywheel(vel);
robot.hood.setPosition(hoodPos);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
return !shouldFinish;
}
};
}
public Action manageShooterAuto(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
double robotX = drive.localizer.getPose().position.x;
double robotY = drive.localizer.getPose().position.y;
double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -15;
double goalY = 0;
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
targetingSettings = targeting.calculateSettings
(robotX, robotY, robotHeading, 0.0, false);
turret.trackGoal(deltaPose);
robot.hood.setPosition(targetingSettings.hoodAngle);
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
return !shouldFinish;
}
};
}
public Action manageFlywheelAuto(
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance
) {
boolean timeFallback = (time != 0.501);
boolean posXFallback = (posX != 0.501);
boolean posYFallback = (posY != 0.501);
return new Action() {
double stamp = 0.0;
int ticker = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
}
ticker++;
double robotX = drive.localizer.getPose().position.x;
double robotY = drive.localizer.getPose().position.y;
double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -15;
double goalY = 0;
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
targetingSettings = targeting.calculateSettings
(robotX, robotY, robotHeading, 0.0, false);
robot.hood.setPosition(targetingSettings.hoodAngle);
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || xDone || yDone;
return !shouldFinish;
}
};
}
@Override
public void runOpMode() throws InterruptedException {
hardwareMap.get(Servo.class, "light").setPosition(0);
robot = new Robot(hardwareMap);
TELE = new MultipleTelemetry(
telemetry, FtcDashboard.getInstance().getTelemetry()
);
flywheel = new Flywheel(hardwareMap);
targeting = new Targeting();
targetingSettings = new Targeting.Settings(0.0, 0.0);
spindexer = new Spindexer(hardwareMap);
servos = new Servos(hardwareMap);
robot.limelight.pipelineSwitch(1);
turret = new Turret(robot, TELE, robot.limelight);
turret.manualSetTurret(0.4);
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
TrajectoryActionBuilder shoot0 = null;
TrajectoryActionBuilder pickup1 = null;
TrajectoryActionBuilder shoot1 = null;
TrajectoryActionBuilder gatePickup = null;
TrajectoryActionBuilder shootCycle = null;
robot.spin1.setPosition(autoSpinStartPos);
robot.spin2.setPosition(1 - autoSpinStartPos);
robot.transferServo.setPosition(transferServo_out);
robot.light.setPosition(1);
while (opModeInInit()) {
robot.hood.setPosition(shoot0Hood);
if (gamepad2.crossWasPressed()) {
redAlliance = !redAlliance;
}
if (redAlliance) {
robot.light.setPosition(0.28);
// ---- FIRST SHOT ----
x1 = rx1;
y1 = ry1;
h1 = rh1;
// ---- PICKUP PATH ----
x2a = rx2a;
y2a = ry2a;
h2a = rh2a;
t2a = rt2a;
x2b = rx2b;
y2b = ry2b;
h2b = rh2b;
t2b = rt2b;
x2c = rx2c;
y2c = ry2c;
h2c = rh2c;
t2c = rt2c;
xShoot = rShootX;
yShoot = rShootY;
hShoot = rShootH;
shoot1Tangent = rShoot1Tangent;
xGate = rXGate;
yGate = rYGate;
hGate = rHGate;
} else {
robot.light.setPosition(0.6);
// ---- FIRST SHOT ----
x1 = bx1;
y1 = by1;
h1 = bh1;
// ---- PICKUP PATH ----
x2a = bx2a;
y2a = by2a;
h2a = bh2a;
t2a = bt2a;
x2b = bx2b;
y2b = by2b;
h2b = bh2b;
t2b = bt2b;
x2c = bx2c;
y2c = by2c;
h2c = bh2c;
t2c = bt2c;
xShoot = bShootX;
yShoot = bShootY;
hShoot = bShootH;
shoot1Tangent = bShoot1Tangent;
xGate = bXGate;
yGate = bYGate;
hGate = bHGate;
}
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
.strafeToLinearHeading(new Vector2d(x1, y1), h1);
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, h1))
.strafeToLinearHeading(new Vector2d(x2a, y2a), h2a)
.strafeToLinearHeading(new Vector2d(x2b, y2b), h2b,
new TranslationalVelConstraint(pickup1Speed));
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, h2b))
.setReversed(true)
.splineTo(new Vector2d(x2a, y2a), shoot1Tangent)
.splineToSplineHeading(new Pose2d(xShoot, yShoot, hShoot), shoot1Tangent);
gatePickup = drive.actionBuilder(new Pose2d(xShoot, yShoot, hShoot))
.strafeToLinearHeading(new Vector2d(xGate, yGate), hGate);
shootCycle = drive.actionBuilder(new Pose2d(xGate, yGate, hGate))
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), hShoot);
}
waitForStart();
if (isStopRequested()) return;
if (opModeIsActive()) {
robot.transfer.setPower(1);
assert shoot0 != null;
Actions.runBlocking(
new ParallelAction(
shoot0.build(),
manageFlywheel(
shoot0Vel,
shoot0Hood,
flywheel0Time,
x1,
0.501,
shoot0XTolerance,
0.501
)
)
);
Actions.runBlocking(
shootAll((int) shoot0Vel, shoot0Time, shoot0SpinSpeedIncrease)
);
Actions.runBlocking(
new ParallelAction(
pickup1.build(),
manageFlywheel(
shootAllVelocity,
shootAllHood,
pickup1Time,
x2b,
y2b,
pickup1XTolerance,
pickup1YTolerance
),
intake(intake1Time),
detectObelisk(
obelisk1Time,
x2b,
y2c,
obelisk1XTolerance,
obelisk1YTolerance,
obeliskTurrPos
)
)
);
motif = turret.detectObelisk();
Actions.runBlocking(
new ParallelAction(
manageFlywheel(
shootAllVelocity,
shootAllHood,
shoot1Time,
0.501,
0.501,
0.501,
0.501
),
shoot1.build(),
prepareShootAll(shoot1Time)
)
);
Actions.runBlocking(
new ParallelAction(
manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501
),
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
while (opModeIsActive()) {
Actions.runBlocking(
new ParallelAction(
gatePickup.build(),
manageShooterAuto(
gatePickupTime,
x2b,
y2b,
pickup1XTolerance,
pickup1YTolerance
),
intake(gatePickupTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageFlywheelAuto(
shootCycleTime,
0.501,
0.501,
0.501,
0.501
),
shootCycle.build(),
prepareShootAll(shootCycleTime)
)
);
Actions.runBlocking(
new ParallelAction(
manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501
),
shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
}
}
}
}

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.autonomous; package org.firstinspires.ftc.teamcode.autonomous.disabled;
import static org.firstinspires.ftc.teamcode.constants.Color.*; import static org.firstinspires.ftc.teamcode.constants.Color.*;
import static org.firstinspires.ftc.teamcode.constants.Poses.*; import static org.firstinspires.ftc.teamcode.constants.Poses.*;
@@ -21,6 +21,7 @@ import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@@ -31,6 +32,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.List; import java.util.List;
@Disabled
@Config @Config
@Autonomous(preselectTeleOp = "TeleopV3") @Autonomous(preselectTeleOp = "TeleopV3")
public class AutoClose_V3 extends LinearOpMode { public class AutoClose_V3 extends LinearOpMode {
@@ -133,8 +135,8 @@ public class AutoClose_V3 extends LinearOpMode {
robot.shooter2.setPower(powPID); robot.shooter2.setPower(powPID);
spinPID = servo.setSpinPos(spindexer); spinPID = servo.setSpinPos(spindexer);
robot.spin1.setPower(spinPID); robot.spin1.setPosition(spinPID);
robot.spin2.setPower(-spinPID); robot.spin2.setPosition(-spinPID);
TELE.addData("Velocity", velo); TELE.addData("Velocity", velo);
TELE.addLine("spindex"); TELE.addLine("spindex");
TELE.update(); TELE.update();
@@ -143,8 +145,8 @@ public class AutoClose_V3 extends LinearOpMode {
teleStart = drive.localizer.getPose(); teleStart = drive.localizer.getPose();
if (servo.spinEqual(spindexer)){ if (servo.spinEqual(spindexer)){
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
return false; return false;
} else { } else {
return true; return true;
@@ -224,8 +226,8 @@ public class AutoClose_V3 extends LinearOpMode {
if (!servo.spinEqual(position)){ if (!servo.spinEqual(position)){
double spinPID = servo.setSpinPos(position); double spinPID = servo.setSpinPos(position);
robot.spin1.setPower(spinPID); robot.spin1.setPosition(spinPID);
robot.spin2.setPower(-spinPID); robot.spin2.setPosition(-spinPID);
} }
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){ if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
@@ -259,8 +261,8 @@ public class AutoClose_V3 extends LinearOpMode {
robot.intake.setPower(1); robot.intake.setPower(1);
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) { if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
if (getRuntime() - stamp - intakeTime < 1){ if (getRuntime() - stamp - intakeTime < 1){
pow = -2*(getRuntime() - stamp - intakeTime); pow = -2*(getRuntime() - stamp - intakeTime);
return true; return true;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.autonomous; package org.firstinspires.ftc.teamcode.autonomous.disabled;
import static org.firstinspires.ftc.teamcode.constants.Color.*; import static org.firstinspires.ftc.teamcode.constants.Color.*;
import static org.firstinspires.ftc.teamcode.constants.Poses.*; import static org.firstinspires.ftc.teamcode.constants.Poses.*;
@@ -21,6 +21,7 @@ import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@@ -30,9 +31,10 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos; import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.List; import java.util.List;
@Disabled
@Config @Config
@Autonomous(preselectTeleOp = "TeleopV3") @Autonomous
public class AutoFar_V1 extends LinearOpMode { public class AutoFar_V1 extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;
@@ -133,8 +135,8 @@ public class AutoFar_V1 extends LinearOpMode {
robot.shooter2.setPower(powPID); robot.shooter2.setPower(powPID);
spinPID = servo.setSpinPos(spindexer); spinPID = servo.setSpinPos(spindexer);
robot.spin1.setPower(spinPID); robot.spin1.setPosition(spinPID);
robot.spin2.setPower(-spinPID); robot.spin2.setPosition(-spinPID);
TELE.addData("Velocity", velo); TELE.addData("Velocity", velo);
TELE.addLine("spindex"); TELE.addLine("spindex");
TELE.update(); TELE.update();
@@ -143,8 +145,8 @@ public class AutoFar_V1 extends LinearOpMode {
teleStart = drive.localizer.getPose(); teleStart = drive.localizer.getPose();
if (servo.spinEqual(spindexer)){ if (servo.spinEqual(spindexer)){
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
return false; return false;
} else { } else {
return true; return true;
@@ -224,8 +226,8 @@ public class AutoFar_V1 extends LinearOpMode {
if (!servo.spinEqual(position)){ if (!servo.spinEqual(position)){
double spinPID = servo.setSpinPos(position); double spinPID = servo.setSpinPos(position);
robot.spin1.setPower(spinPID); robot.spin1.setPosition(spinPID);
robot.spin2.setPower(-spinPID); robot.spin2.setPosition(-spinPID);
} }
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){ if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
@@ -259,8 +261,8 @@ public class AutoFar_V1 extends LinearOpMode {
robot.intake.setPower(1); robot.intake.setPower(1);
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) { if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
if (getRuntime() - stamp - intakeTime < 1){ if (getRuntime() - stamp - intakeTime < 1){
pow = -2*(getRuntime() - stamp - intakeTime); pow = -2*(getRuntime() - stamp - intakeTime);
return true; return true;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.autonomous; package org.firstinspires.ftc.teamcode.autonomous.disabled;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance; import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Poses.bh1; import static org.firstinspires.ftc.teamcode.constants.Poses.bh1;
@@ -72,6 +72,7 @@ import com.acmerobotics.roadrunner.ftc.Actions;
import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@@ -81,7 +82,7 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos; import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.List; import java.util.List;
@Disabled
@Config @Config
@Autonomous(preselectTeleOp = "TeleopV3") @Autonomous(preselectTeleOp = "TeleopV3")
public class ProtoAutoClose_V3 extends LinearOpMode { public class ProtoAutoClose_V3 extends LinearOpMode {
@@ -182,8 +183,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
velo = flywheel.getVelo(); velo = flywheel.getVelo();
spinPID = servo.setSpinPos(spindexer); spinPID = servo.setSpinPos(spindexer);
robot.spin1.setPower(spinPID); robot.spin1.setPosition(spinPID);
robot.spin2.setPower(-spinPID); robot.spin2.setPosition(-spinPID);
TELE.addData("Velocity", velo); TELE.addData("Velocity", velo);
TELE.addLine("spindex"); TELE.addLine("spindex");
TELE.update(); TELE.update();
@@ -192,8 +193,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
teleStart = drive.localizer.getPose(); teleStart = drive.localizer.getPose();
if (servo.spinEqual(spindexer)) { if (servo.spinEqual(spindexer)) {
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
return false; return false;
} else { } else {
@@ -203,6 +204,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
}; };
} }
public Action Shoot(int vel) { public Action Shoot(int vel) {
return new Action() { return new Action() {
int ticker = 1; int ticker = 1;
@@ -240,8 +242,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
robot.transferServo.setPosition(transferServo_in); robot.transferServo.setPosition(transferServo_in);
robot.spin1.setPower(-spinPow); robot.spin1.setPosition(-spinPow);
robot.spin2.setPower(spinPow); robot.spin2.setPosition(spinPow);
return true; return true;
} else { } else {
@@ -271,12 +273,12 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
if (ticker % 12 < 6) { if (ticker % 12 < 6) {
robot.spin1.setPower(-1); robot.spin1.setPosition(-1);
robot.spin2.setPower(1); robot.spin2.setPosition(1);
} else { } else {
robot.spin1.setPower(1); robot.spin1.setPosition(1);
robot.spin2.setPower(-1); robot.spin2.setPosition(-1);
} }
if (getRuntime() - stamp > jamTime+0.4) { if (getRuntime() - stamp > jamTime+0.4) {
@@ -317,20 +319,20 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
if (ticker % 60 < 12) { if (ticker % 60 < 12) {
robot.spin1.setPower(-1); robot.spin1.setPosition(-1);
robot.spin2.setPower(1); robot.spin2.setPosition(1);
} else if (ticker % 60 < 30) { } else if (ticker % 60 < 30) {
robot.spin1.setPower(-0.5); robot.spin1.setPosition(-0.5);
robot.spin2.setPower(0.5); robot.spin2.setPosition(0.5);
} }
else if (ticker % 60 < 42) { else if (ticker % 60 < 42) {
robot.spin1.setPower(1); robot.spin1.setPosition(1);
robot.spin2.setPower(-1); robot.spin2.setPosition(-1);
} }
else { else {
robot.spin1.setPower(0.5); robot.spin1.setPosition(0.5);
robot.spin2.setPower(-0.5); robot.spin2.setPosition(-0.5);
} }
robot.intake.setPower(1); robot.intake.setPower(1);
TELE.addData("Reverse?", reverse); TELE.addData("Reverse?", reverse);
@@ -338,11 +340,11 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
if (getRuntime() - stamp > intakeTime) { if (getRuntime() - stamp > intakeTime) {
if (reverse) { if (reverse) {
robot.spin1.setPower(-1); robot.spin1.setPosition(-1);
robot.spin2.setPower(1); robot.spin2.setPosition(1);
} else { } else {
robot.spin1.setPower(1); robot.spin1.setPosition(1);
robot.spin2.setPower(-1); robot.spin2.setPosition(-1);
} }
return false; return false;
} else { } else {
@@ -710,7 +712,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
bearing = result.getTx(); bearing = result.getTx();
} }
} }
double turretPos = robot.turr1Pos.getCurrentPosition() - (bearing / 1300); double turretPos = (bearing / 1300);
robot.turr1.setPosition(turretPos); robot.turr1.setPosition(turretPos);
robot.turr2.setPosition(1 - turretPos); robot.turr2.setPosition(1 - turretPos);
} }

View File

@@ -1,5 +1,11 @@
package org.firstinspires.ftc.teamcode.constants; package org.firstinspires.ftc.teamcode.constants;
import com.acmerobotics.dashboard.config.Config;
@Config
public class Color { public class Color {
public static boolean redAlliance = true; public static boolean redAlliance = true;
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
public static double colorFilterAlpha = 0.15;
} }

View File

@@ -12,19 +12,19 @@ public class Poses {
public static double relativeGoalHeight = goalHeight - turretHeight; public static double relativeGoalHeight = goalHeight - turretHeight;
public static Pose2d goalPose = new Pose2d(-15, 0, 0); public static Pose2d goalPose = new Pose2d(-10, 0, 0);
public static double rx1 = 40, ry1 = -7, rh1 = 0; public static double rx1 = 20, ry1 = 0.5, rh1 = Math.toRadians(0.1);
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140); public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140); public static double rx2b = 23, ry2b = 36, rh2b = Math.toRadians(140.1);
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140); public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140);
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140); public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140); public static double rx3b = 38, ry3b = 56, rh3b = Math.toRadians(140.1);
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140); public static double rx4a = 72, ry4a = 65, rh4a = Math.toRadians(145);
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140); public static double rx4b = 37, ry4b = 85, rh4b = Math.toRadians(145.1);
public static double bx1 = 40, by1 = 7, bh1 = 0; public static double bx1 = 40, by1 = 7, bh1 = 0;
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140); public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140);
@@ -38,6 +38,13 @@ public class Poses {
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140); public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1); public static double rShootX = 40, rShootY = -7, rShootH = Math.toRadians(50);
public static double rxPrep = 45, ryPrep = 10, rhPrep = Math.toRadians(50);
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
public static double bxPrep = 50, byPrep = -10, bhPrep = Math.toRadians(140);
public static Pose2d teleStart = new Pose2d(0, 0, 0);
} }

View File

@@ -0,0 +1,86 @@
package org.firstinspires.ftc.teamcode.constants;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.Pose2d;
@Config
public class Poses_LT_Indexed {
// ================= FIELD / GOAL =================
public static double goalHeight = 42; // inches
public static double turretHeight = 12;
public static double relativeGoalHeight = goalHeight - turretHeight;
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
public static Pose2d teleStart = new Pose2d(0, 0, 0);
// =================================================
// ================= RED ALLIANCE ==================
// =================================================
// -------- FIRST SHOT --------
public static double rx1 = 20, ry1 = 0, rh1 = 0;
// -------- PICKUP 1 --------
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI / 2);
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI / 2);
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI / 2);
// -------- OPEN GATE --------
public static double rXGate = 30, rYGate = 63, rHGate = Math.toRadians(179);
// -------- PICKUP 2 --------
public static double rx3 = 0, ry3 = 0, rh3 = 0, rt3 = 0;
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
// -------- PICKUP 3 --------
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
public static double rx5a = 0, ry5a = 0, rh5a = 0;
public static double rx5b = 0, ry5b = 0, rh5b = 0;
// -------- SHOOT --------
public static double rShootX = 40, rShootY = 7, rShootH = Math.toRadians(140);
public static double rShoot1Tangent = Math.toRadians(0);
// -------- PARK --------
public static double rXPark = 0, rYPark = 0, rHPark = 0;
// =================================================
// ================= BLUE ALLIANCE =================
// =================================================
// -------- FIRST SHOT --------
public static double bx1 = 20, by1 = 0, bh1 = 0;
// -------- PICKUP 1 --------
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
// -------- OPEN GATE --------
public static double bXGate = 25, bYGate = 69, bHGate = Math.toRadians(165);
// -------- PICKUP 2 --------
public static double bx3 = 0, by3 = 0, bh3 = 0, bt3 = 0;
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
// -------- PICKUP 3 --------
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
public static double bx5a = 0, by5a = 0, bh5a = 0;
public static double bx5b = 0, by5b = 0, bh5b = 0;
// -------- SHOOT --------
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
public static double bShoot1Tangent = Math.toRadians(0);
// -------- PARK --------
public static double bXPark = 0, bYPark = 0, bHPark = 0;
}

View File

@@ -0,0 +1,56 @@
package org.firstinspires.ftc.teamcode.constants;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.Pose2d;
@Config
public class Poses_V2 {
public static double goalHeight = 42; //in inches
public static double turretHeight = 12;
public static double relativeGoalHeight = goalHeight - turretHeight;
public static Pose2d goalPose = new Pose2d(-10, 0, 0);
public static double rx1 = 20, ry1 = 0, rh1 = 0;
public static double rx2a = 55, ry2a = 39, rh2a = Math.toRadians(140), rt2a = Math.toRadians(Math.PI/2);
public static double rx2b = 33, ry2b = 61, rh2b = Math.toRadians(140), rt2b = Math.toRadians(Math.PI/2);
public static double rx2c = 34, ry2c = 50, rh2c = Math.toRadians(140), rt2c = Math.toRadians(Math.PI/2);
public static double rXGate = 30, rYGate = 63, rHGate = Math.toRadians(179);
public static double rx3a = 55, ry3a = 39, rh3a = Math.toRadians(140);
public static double rx3b = 33, ry3b = 61, rh3b = Math.toRadians(140);
public static double rx4a = 72, ry4a = 55, rh4a = Math.toRadians(140);
public static double rx4b = 48, ry4b = 79, rh4b = Math.toRadians(140);
public static double bx1 = 20, by1 = 0, bh1 = 0;
public static double bx2a = 45, by2a = -18, bh2a = Math.toRadians(-140), bt2a = Math.toRadians(140);
public static double bx2b = 25, by2b = -38, bh2b = Math.toRadians(-140), bt2b = Math.toRadians(140);
public static double bx2c = 34, by2c = -50, bh2c = Math.toRadians(-140), bt2c = Math.toRadians(140);
public static double rShootX = 40, rShootY = 7, rShootH = Math.toRadians(140);
public static double bShootX = 20, bShootY = 30, bShootH = Math.toRadians(140);
public static double bXGate = 25, bYGate = 69, bHGate = Math.toRadians(165);
public static double bx3a = 55, by3a = -43, bh3a = Math.toRadians(-140);
public static double bx3b = 37, by3b = -61, bh3b = Math.toRadians(-140);
public static double bx4a = 72, by4a = -55, bh4a = Math.toRadians(-140);
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
public static double rShoot1Tangent = Math.toRadians(0);
public static double bShoot1Tangent = Math.toRadians(0);
public static Pose2d teleStart = new Pose2d(0, 0, 0);
}

View File

@@ -5,16 +5,21 @@ import com.acmerobotics.dashboard.config.Config;
@Config @Config
public class ServoPositions { public class ServoPositions {
public static double spindexer_intakePos1 = 0.19; public static double spindexer_intakePos1 = 0.05; //0.13;
public static double spindexer_intakePos2 = 0.35;//0.5; public static double spindexer_intakePos2 = 0.24; //0.33;//0.5;
public static double spindexer_intakePos3 = 0.51;//0.66; public static double spindexer_intakePos3 = 0.43; //0.53;//0.66;
public static double spindexer_outtakeBall3 = 0.47; public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
public static double spindexer_outtakeBall2 = 0.31; public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
public static double spindexer_outtakeBall1 = 0.15; public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
public static double spinStartPos = spindexer_outtakeBall3 - 0.1;
public static double shootAllAutoSpinStartPos = 0.2;
public static double shootAllSpindexerSpeedIncrease = 0.02;
public static double shootAllTime = 1.8;
public static double transferServo_out = 0.15; public static double transferServo_out = 0.15;
@@ -42,4 +47,8 @@ public class ServoPositions {
public static double turret_detectBlueClose = 0.6; public static double turret_detectBlueClose = 0.6;
public static double turrDefault = 0.4; public static double turrDefault = 0.4;
public static double turrMin = 0.2;
public static double turrMax = 0.8;
} }

View File

@@ -21,4 +21,6 @@ public class ShooterVars {
// VELOCITY CONSTANTS // VELOCITY CONSTANTS
public static int AUTO_CLOSE_VEL = 3175; //3300; public static int AUTO_CLOSE_VEL = 3175; //3300;
public static int AUTO_FAR_VEL = 4000; //TODO: test this public static int AUTO_FAR_VEL = 4000; //TODO: test this
public static Types.Motif currentMotif = Types.Motif.NONE;
} }

View File

@@ -0,0 +1,10 @@
package org.firstinspires.ftc.teamcode.constants;
public class Types {
public enum Motif {
NONE,
GPP, // Green, Purple, Purple
PGP, // Purple, Green, Purple
PPG // Purple, Purple, Green
}
}

View File

@@ -1,4 +0,0 @@
package org.firstinspires.ftc.teamcode.constants;
public class blank {
}

View File

@@ -5,9 +5,7 @@ import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.canvas.Canvas;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket; import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.AccelConstraint; import com.acmerobotics.roadrunner.*;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.Actions;
import com.acmerobotics.roadrunner.AngularVelConstraint; import com.acmerobotics.roadrunner.AngularVelConstraint;
import com.acmerobotics.roadrunner.DualNum; import com.acmerobotics.roadrunner.DualNum;
import com.acmerobotics.roadrunner.HolonomicController; import com.acmerobotics.roadrunner.HolonomicController;
@@ -16,20 +14,12 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
import com.acmerobotics.roadrunner.MotorFeedforward; import com.acmerobotics.roadrunner.MotorFeedforward;
import com.acmerobotics.roadrunner.Pose2d; import com.acmerobotics.roadrunner.Pose2d;
import com.acmerobotics.roadrunner.Pose2dDual; import com.acmerobotics.roadrunner.Pose2dDual;
import com.acmerobotics.roadrunner.PoseVelocity2d;
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
import com.acmerobotics.roadrunner.ProfileAccelConstraint; import com.acmerobotics.roadrunner.ProfileAccelConstraint;
import com.acmerobotics.roadrunner.ProfileParams;
import com.acmerobotics.roadrunner.Rotation2d;
import com.acmerobotics.roadrunner.Time; import com.acmerobotics.roadrunner.Time;
import com.acmerobotics.roadrunner.TimeTrajectory; import com.acmerobotics.roadrunner.TimeTrajectory;
import com.acmerobotics.roadrunner.TimeTurn; import com.acmerobotics.roadrunner.TimeTurn;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder; import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
import com.acmerobotics.roadrunner.TurnConstraints; import com.acmerobotics.roadrunner.TurnConstraints;
import com.acmerobotics.roadrunner.Twist2d;
import com.acmerobotics.roadrunner.Twist2dDual;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.VelConstraint; import com.acmerobotics.roadrunner.VelConstraint;
import com.acmerobotics.roadrunner.ftc.DownsampledWriter; import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
import com.acmerobotics.roadrunner.ftc.Encoder; import com.acmerobotics.roadrunner.ftc.Encoder;
@@ -56,131 +46,13 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage; import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage; import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
import java.lang.Math;
import java.util.Arrays; import java.util.Arrays;
import java.util.LinkedList; import java.util.LinkedList;
import java.util.List; import java.util.List;
@Config @Config
public final class MecanumDrive { public final class MecanumDrive {
public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics(
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel)
));
public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
public final VoltageSensor voltageSensor;
public final LazyImu lazyImu;
public final Localizer localizer;
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
// TODO: make sure your config has motors with these names (or change them)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
rightBack = hardwareMap.get(DcMotorEx.class, "br");
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// TODO: reverse motor directions if needed
//
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}
public void setDrivePowers(PoseVelocity2d powers) {
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
PoseVelocity2dDual.constant(powers, 1));
double maxPowerMag = 1;
for (DualNum<Time> power : wheelVels.all()) {
maxPowerMag = Math.max(maxPowerMag, power.value());
}
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
}
public PoseVelocity2d updatePoseEstimate() {
PoseVelocity2d vel = localizer.update();
poseHistory.add(localizer.getPose());
while (poseHistory.size() > 100) {
poseHistory.removeFirst();
}
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
return vel;
}
private void drawPoseHistory(Canvas c) {
double[] xPoints = new double[poseHistory.size()];
double[] yPoints = new double[poseHistory.size()];
int i = 0;
for (Pose2d t : poseHistory) {
xPoints[i] = t.position.x;
yPoints[i] = t.position.y;
i++;
}
c.setStrokeWidth(1);
c.setStroke("#3F51B5");
c.strokePolyline(xPoints, yPoints);
}
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
return new TrajectoryActionBuilder(
TurnAction::new,
FollowTrajectoryAction::new,
new TrajectoryBuilderParams(
1e-6,
new ProfileParams(
0.25, 0.1, 1e-2
)
),
beginPose, 0.0,
defaultTurnConstraints,
defaultVelConstraint, defaultAccelConstraint
);
}
public static class Params { public static class Params {
// IMU orientation // IMU orientation
// TODO: fill in these values based on // TODO: fill in these values based on
@@ -206,8 +78,8 @@ public final class MecanumDrive {
public double maxProfileAccel = 180; public double maxProfileAccel = 180;
// turn profile parameters (in radians) // turn profile parameters (in radians)
public double maxAngVel = 4 * Math.PI; // shared with path public double maxAngVel = 4* Math.PI; // shared with path
public double maxAngAccel = 4 * Math.PI; public double maxAngAccel = 4* Math.PI;
// path controller gains // path controller gains
public double axialGain = 4; public double axialGain = 4;
@@ -219,6 +91,35 @@ public final class MecanumDrive {
public double headingVelGain = 0.0; // shared with turn public double headingVelGain = 0.0; // shared with turn
} }
public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics(
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel)
));
public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
public final VoltageSensor voltageSensor;
public final LazyImu lazyImu;
public final Localizer localizer;
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
public class DriveLocalizer implements Localizer { public class DriveLocalizer implements Localizer {
public final Encoder leftFront, leftBack, rightBack, rightFront; public final Encoder leftFront, leftBack, rightBack, rightFront;
public final IMU imu; public final IMU imu;
@@ -243,13 +144,13 @@ public final class MecanumDrive {
} }
@Override @Override
public Pose2d getPose() { public void setPose(Pose2d pose) {
return pose; this.pose = pose;
} }
@Override @Override
public void setPose(Pose2d pose) { public Pose2d getPose() {
this.pose = pose; return pose;
} }
@Override @Override
@@ -315,11 +216,64 @@ public final class MecanumDrive {
} }
} }
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
// TODO: make sure your config has motors with these names (or change them)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
rightBack = hardwareMap.get(DcMotorEx.class, "br");
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// TODO: reverse motor directions if needed
//
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}
public void setDrivePowers(PoseVelocity2d powers) {
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
PoseVelocity2dDual.constant(powers, 1));
double maxPowerMag = 1;
for (DualNum<Time> power : wheelVels.all()) {
maxPowerMag = Math.max(maxPowerMag, power.value());
}
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
}
public final class FollowTrajectoryAction implements Action { public final class FollowTrajectoryAction implements Action {
public final TimeTrajectory timeTrajectory; public final TimeTrajectory timeTrajectory;
private final double[] xPoints, yPoints;
private double beginTs = -1; private double beginTs = -1;
private final double[] xPoints, yPoints;
public FollowTrajectoryAction(TimeTrajectory t) { public FollowTrajectoryAction(TimeTrajectory t) {
timeTrajectory = t; timeTrajectory = t;
@@ -496,4 +450,51 @@ public final class MecanumDrive {
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2); c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
} }
} }
public PoseVelocity2d updatePoseEstimate() {
PoseVelocity2d vel = localizer.update();
poseHistory.add(localizer.getPose());
while (poseHistory.size() > 100) {
poseHistory.removeFirst();
}
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
return vel;
}
private void drawPoseHistory(Canvas c) {
double[] xPoints = new double[poseHistory.size()];
double[] yPoints = new double[poseHistory.size()];
int i = 0;
for (Pose2d t : poseHistory) {
xPoints[i] = t.position.x;
yPoints[i] = t.position.y;
i++;
}
c.setStrokeWidth(1);
c.setStroke("#3F51B5");
c.strokePolyline(xPoints, yPoints);
}
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
return new TrajectoryActionBuilder(
TurnAction::new,
FollowTrajectoryAction::new,
new TrajectoryBuilderParams(
1e-6,
new ProfileParams(
0.25, 0.1, 1e-2
)
),
beginPose, 0.0,
defaultTurnConstraints,
defaultVelConstraint, defaultAccelConstraint
);
}
} }

View File

@@ -162,11 +162,11 @@ public class TeleopV2 extends LinearOpMode {
//TODO: make sure changing position works throughout opmode //TODO: make sure changing position works throughout opmode
if (!servo.spinEqual(spindexPos)){ if (!servo.spinEqual(spindexPos)){
spindexPID = servo.setSpinPos(spindexPos); spindexPID = servo.setSpinPos(spindexPos);
robot.spin1.setPower(spindexPID); robot.spin1.setPosition(spindexPID);
robot.spin2.setPower(-spindexPID); robot.spin2.setPosition(-spindexPID);
} else{ } else{
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
} }
//INTAKE: //INTAKE:

View File

@@ -2,10 +2,14 @@ package org.firstinspires.ftc.teamcode.teleop;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance; import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart; import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_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_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out; 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.utils.Servos.spinD; import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF; import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI; import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
@@ -21,18 +25,21 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions; import com.acmerobotics.roadrunner.ftc.Actions;
import com.arcrobotics.ftclib.controller.PIDFController; import com.arcrobotics.ftclib.controller.PIDFController;
import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; 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.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos; import org.firstinspires.ftc.teamcode.utils.Servos;
import org.firstinspires.ftc.teamcode.utils.Spindexer; import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.List; import java.util.List;
@@ -53,6 +60,8 @@ public class TeleopV3 extends LinearOpMode {
public static boolean manualTurret = true; public static boolean manualTurret = true;
public double vel = 3000; public double vel = 3000;
public boolean autoVel = true; public boolean autoVel = true;
public boolean targetingVel = true;
public boolean targetingHood = true;
public double manualOffset = 0.0; public double manualOffset = 0.0;
public boolean autoHood = true; public boolean autoHood = true;
public boolean green1 = false; public boolean green1 = false;
@@ -72,6 +81,8 @@ public class TeleopV3 extends LinearOpMode {
Flywheel flywheel; Flywheel flywheel;
MecanumDrive drive; MecanumDrive drive;
Spindexer spindexer; Spindexer spindexer;
Targeting targeting;
Targeting.Settings targetingSettings;
double autoHoodOffset = 0.0; double autoHoodOffset = 0.0;
int shooterTicker = 0; int shooterTicker = 0;
@@ -116,6 +127,9 @@ public class TeleopV3 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;
boolean turretInterpolate = false;
public static double spinSpeedIncrease = 0.03;
public static int resetSpinTicks = 4;
public static double velPrediction(double distance) { public static double velPrediction(double distance) {
if (distance < 30) { if (distance < 30) {
@@ -134,30 +148,45 @@ public class TeleopV3 extends LinearOpMode {
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
robot = new Robot(hardwareMap);
robot.light.setPosition(0);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class); List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) { for (LynxModule hub : allHubs) {
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL); hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
} }
robot = new Robot(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
servo = new Servos(hardwareMap); servo = new Servos(hardwareMap);
flywheel = new Flywheel(hardwareMap); flywheel = new Flywheel(hardwareMap);
drive = new MecanumDrive(hardwareMap, teleStart); drive = new MecanumDrive(hardwareMap, teleStart);
spindexer = new Spindexer(hardwareMap); spindexer = new Spindexer(hardwareMap);
targeting = new Targeting();
targetingSettings = new Targeting.Settings(0.0, 0.0);
PIDFController tController = new PIDFController(tp, ti, td, tf); PIDFController tController = new PIDFController(tp, ti, td, tf);
tController.setTolerance(0.001); tController.setTolerance(0.001);
//
// if (redAlliance) {
// robot.limelight.pipelineSwitch(3);
// } else {
// robot.limelight.pipelineSwitch(2);
// }
// robot.limelight.start();
Turret turret = new Turret(robot, TELE, robot.limelight);
robot.light.setPosition(1);
while (opModeInInit()){
robot.limelight.start();
if (redAlliance) { if (redAlliance) {
robot.limelight.pipelineSwitch(3); robot.limelight.pipelineSwitch(4);
} else { } else {
robot.limelight.pipelineSwitch(2); robot.limelight.pipelineSwitch(2);
} }
}
robot.limelight.start();
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
@@ -165,6 +194,12 @@ public class TeleopV3 extends LinearOpMode {
robot.transferServo.setPosition(transferServo_out); robot.transferServo.setPosition(transferServo_out);
while (opModeIsActive()) { while (opModeIsActive()) {
//LIMELIGHT START
TELE.addData("Is limelight on?", robot.limelight.getStatus());
// LIGHT COLORS
spindexer.ballCounterLight();
//DRIVETRAIN: //DRIVETRAIN:
double y = 0.0; double y = 0.0;
@@ -223,64 +258,62 @@ public class TeleopV3 extends LinearOpMode {
//TODO: Use color sensors to switch between positions...switch after ball detected in //TODO: Use color sensors to switch between positions...switch after ball detected in
if (autoSpintake) { if (gamepad1.right_bumper){
shootAll = false;
if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) { robot.transferServo.setPosition(transferServo_out);
spinCurrentPos = servo.getSpinPos();
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos);
robot.spin1.setPower(spindexPID);
robot.spin2.setPower(-spindexPID);
} }
if (gamepad1.right_bumper) { // if (autoSpintake) {
//
intakeTicker++; // if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) {
//
if (intakeTicker % 20 < 2) { //
// robot.spin1.setPosition(spindexPos);
robot.spin1.setPower(-1); // robot.spin2.setPosition(1-spindexPos);
robot.spin2.setPower(1); //
// }
} else if (intakeTicker % 20 < 10) { //
robot.spin1.setPower(-0.5); // if (gamepad1.right_bumper) {
robot.spin2.setPower(0.5); //
} else if (intakeTicker % 20 < 12) { // shootAll = false;
robot.spin1.setPower(1); //
robot.spin2.setPower(-1); // intakeTicker++;
} else { //
robot.spin1.setPower(0.5); //// if (intakeTicker % 20 < 2) {
robot.spin2.setPower(-0.5); ////
} //// robot.spin1.setPower(-1);
//// robot.spin2.setPower(1);
robot.intake.setPower(1); ////
intakeStamp = getRuntime(); //// } else if (intakeTicker % 20 < 10) {
TELE.addData("Reverse?", reverse); //// robot.spin1.setPower(-0.5);
TELE.update(); //// robot.spin2.setPower(0.5);
} else { //// } else if (intakeTicker % 20 < 12) {
if (!servo.spinEqual(spindexPos)) { //// robot.spin1.setPower(1);
spinCurrentPos = servo.getSpinPos(); //// robot.spin2.setPower(-1);
//// } else {
double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos); //// robot.spin1.setPower(0.5);
//// robot.spin2.setPower(-0.5);
robot.spin1.setPower(spindexPID); //// }
robot.spin2.setPower(-spindexPID); //
// robot.intake.setPower(1);
} else { // intakeStamp = getRuntime();
// TELE.addData("Reverse?", reverse);
robot.spin1.setPower(0); // TELE.update();
robot.spin2.setPower(0); // } else {
} // if (!servo.spinEqual(spindexPos)) {
// robot.spin1.setPosition(spindexPos);
spindexPos = spindexer_intakePos1; // robot.spin2.setPosition(1-spindexPos);
//
robot.intake.setPower(0); // }
//
intakeTicker = 0; // spindexPos = spindexer_intakePos1;
} //
} // robot.intake.setPower(0);
//
// intakeTicker = 0;
// }
// }
//COLOR: //COLOR:
@@ -372,43 +405,24 @@ public class TeleopV3 extends LinearOpMode {
double robotY = robY - yOffset; double robotY = robY - yOffset;
double robotHeading = drive.localizer.getPose().heading.toDouble(); double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -10; double goalX = -15;
double goalY = 0; double goalY = 0;
double dx = goalX - robotX; // delta x from robot to goal double dx = robotX - goalX; // delta x from robot to goal
double dy = goalY - robotY; // delta y from robot to goal double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy); double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360; targetingSettings = targeting.calculateSettings
(robotX,robotY,robotHeading,0.0, turretInterpolate);
desiredTurretAngle += manualOffset + error; turret.trackGoal(deltaPose);
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
if (offset > 135) {
offset -= 360;
}
double pos = turrDefault;
TELE.addData("offset", offset);
pos -= offset * ((double) 1 / 360);
if (pos < 0.13) {
pos = 0.13;
} else if (pos > 0.83) {
pos = 0.83;
}
//SHOOTER:
flywheel.manageFlywheel(vel);
//VELOCITY AUTOMATIC //VELOCITY AUTOMATIC
if (targetingVel) {
if (autoVel) { vel = targetingSettings.flywheelRPM;
} else if (autoVel) {
vel = velPrediction(distanceToGoal); vel = velPrediction(distanceToGoal);
} else { } else {
vel = manualVel; vel = manualVel;
@@ -430,57 +444,39 @@ public class TeleopV3 extends LinearOpMode {
manualVel = 3100; manualVel = 3100;
} }
//SHOOTER:
flywheel.manageFlywheel(vel);
//TODO: test the camera teleop code //TODO: test the camera teleop code
TELE.addData("posS2", pos); // if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
// double bearing;
if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving //
double bearing; // LLResult result = robot.light.getLatestResult();
// if (result != null) {
LLResult result = robot.limelight.getLatestResult(); // if (result.isValid()) {
if (result != null) { // bearing = result.getTx() * bMult;
if (result.isValid()) { //
bearing = result.getTx() * bMult; // double bearingCorrection = bearing / bDiv;
//
double bearingCorrection = bearing / bDiv; // error += bearingCorrection;
//
error += bearingCorrection; // camTicker++;
// TELE.addData("tx", bearingCorrection);
camTicker++; // TELE.addData("ty", result.getTy());
TELE.addData("tx", bearingCorrection); // }
TELE.addData("ty", result.getTy()); // }
} //
} // } else {
// camTicker = 0;
} else { // overrideTurr = false;
camTicker = 0; // }
overrideTurr = false;
}
if (!overrideTurr) {
turretPos = pos;
}
TELE.addData("posS3", turretPos);
if (manualTurret) {
pos = turrDefault + (manualOffset / 100) + error;
}
if (!overrideTurr) {
turretPos = pos;
}
if (Math.abs(gamepad2.left_stick_x)>0.2) {
manualOffset += 1.35 * gamepad2.left_stick_x;
}
robot.turr1.setPosition(pos);
robot.turr2.setPosition(1 - pos);
//HOOD: //HOOD:
if (autoHood) { if (targetingHood) {
robot.hood.setPosition(targetingSettings.hoodAngle);
} else if (autoHood) {
robot.hood.setPosition(0.15 + hoodOffset); robot.hood.setPosition(0.15 + hoodOffset);
} else { } else {
robot.hood.setPosition(hoodDefaultPos + hoodOffset); robot.hood.setPosition(hoodDefaultPos + hoodOffset);
@@ -533,132 +529,179 @@ public class TeleopV3 extends LinearOpMode {
// } // }
// } // }
if (gamepad1.left_bumper && !enableSpindexerManager) { //if (gamepad1.left_bumper && !enableSpindexerManager) {
robot.transferServo.setPosition(transferServo_out); // robot.transferServo.setPosition(transferServo_out);
autoSpintake = false; // autoSpintake = false;
//
intakeTicker++; // intakeTicker++;
//
if (intakeTicker % 10 < 1) { // if (intakeTicker % 10 < 1) {
//
robot.spin1.setPower(-1); // robot.spin1.setPower(-1);
robot.spin2.setPower(1); // robot.spin2.setPower(1);
//
} else if (intakeTicker % 10 < 5) { // } else if (intakeTicker % 10 < 5) {
robot.spin1.setPower(-0.5); // robot.spin1.setPower(-0.5);
robot.spin2.setPower(0.5); // robot.spin2.setPower(0.5);
} else if (intakeTicker % 10 < 6) { // } else if (intakeTicker % 10 < 6) {
robot.spin1.setPower(1); // robot.spin1.setPower(1);
robot.spin2.setPower(-1); // robot.spin2.setPower(-1);
} else { // } else {
robot.spin1.setPower(0.5); // robot.spin1.setPower(0.5);
robot.spin2.setPower(-0.5); // robot.spin2.setPower(-0.5);
} // }
//
intake = false; // intake = false;
reject = false; // reject = false;
//
robot.intake.setPower(0.5); // robot.intake.setPower(0.5);
//
} // }
//
if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) { // if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) {
shootStamp = getRuntime(); // shootStamp = getRuntime();
shootAll = true; // shootAll = true;
//
shooterTicker = 0; // shooterTicker = 0;
} // }
//
if (shootAll && !enableSpindexerManager) { // if (shootAll && !enableSpindexerManager) {
//
TELE.addData("100% works", shootOrder); // TELE.addData("100% works", shootOrder);
//
intake = false; // intake = false;
reject = false; // reject = false;
//
shooterTicker++; // shooterTicker++;
//
spindexPos = spindexer_intakePos1; // spindexPos = spindexer_intakePos1;
//
if (getRuntime() - shootStamp < 3.5) { // if (getRuntime() - shootStamp < 3.5) {
//
robot.transferServo.setPosition(transferServo_in); // robot.transferServo.setPosition(transferServo_in);
//
autoSpintake = false; // autoSpintake = false;
//
robot.spin1.setPower(-spinPow); // robot.spin1.setPower(-spinPow);
robot.spin2.setPower(spinPow); // robot.spin2.setPower(spinPow);
//
} else { // } else {
robot.transferServo.setPosition(transferServo_out); // robot.transferServo.setPosition(transferServo_out);
spindexPos = spindexer_intakePos1; // spindexPos = spindexer_intakePos1;
//
shootAll = false; // shootAll = false;
//
autoSpintake = true; // autoSpintake = true;
//
robot.transferServo.setPosition(transferServo_out); // robot.transferServo.setPosition(transferServo_out);
} // }
//
} // }
if (enableSpindexerManager) { if (enableSpindexerManager) {
if (!shootAll) { //if (!shootAll) {
spindexer.processIntake(); spindexer.processIntake();
} //}
// RIGHT_BUMPER // RIGHT_BUMPER
if (gamepad1.right_bumper) { if (gamepad1.right_bumper && intakeTicker > resetSpinTicks) {
robot.intake.setPower(1); robot.intake.setPower(1);
} else { } else {
robot.intake.setPower(0); robot.intake.setPower(0);
} }
// LEFT_BUMPER // LEFT_BUMPER
if (!shootAll && if (!shootAll && gamepad1.leftBumperWasReleased()) {
(gamepad1.leftBumperWasReleased() ||
gamepad1.leftBumperWasPressed() ||
gamepad1.left_bumper)) {
shootStamp = getRuntime(); shootStamp = getRuntime();
shootAll = true; shootAll = true;
shooterTicker = 0; shooterTicker = 0;
} }
intakeTicker++;
if (shootAll) { if (shootAll) {
intakeTicker = 0;
intake = false; intake = false;
reject = false; reject = false;
shooterTicker++; // if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4) {
//
// if (shooterTicker == 0){
// robot.transferServo.setPosition(transferServo_out);
// robot.spin1.setPosition(spinStartPos);
// robot.spin2.setPosition(1-spinStartPos);
// if (servo.spinEqual(spinStartPos)){
// shooterTicker++;
// }
// TELE.addLine("starting to shoot");
// } else {
// robot.transferServo.setPosition(transferServo_in);
// shooterTicker++;
// double prevSpinPos = servo.getSpinPos();
// robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
// robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
// TELE.addLine("shooting");
// }
// TODO: Change starting position based on desired order to shoot green ball // //robot.intake.setPower(-0.3);
spindexPos = spindexer_intakePos1; // if (getRuntime() - shootStamp < 3.0) {
//
// if (shooterTicker == 0 && !servo.spinEqual(ServoPositions.shootAllAutoSpinStartPos)) {
// robot.spin1.setPosition(ServoPositions.shootAllAutoSpinStartPos);
// robot.spin2.setPosition(1 - ServoPositions.shootAllAutoSpinStartPos);
// } else {
// shooterTicker++;
// //robot.intake.setPower(0.0);
// robot.transferServo.setPosition(transferServo_in);
// double prevSpinPos = robot.spin1.getPosition();
// robot.spin1.setPosition(prevSpinPos + ServoPositions.shootAllSpindexerSpeedIncrease);
// robot.spin2.setPosition(1 - prevSpinPos - ServoPositions.shootAllAutoSpinStartPos);
// }
//
// } else {
// robot.transferServo.setPosition(transferServo_out);
// //spindexPos = spindexer_intakePos1;
// shootAll = false;
// spindexer.resetSpindexer();
// spindexer.processIntake();
//
// }
if (getRuntime() - shootStamp < 3.5) {
if (shooterTicker == 0) {
spindexer.prepareShootAll();
TELE.addLine("preparing to shoot");
} else if (shooterTicker == 2) {
//robot.transferServo.setPosition(transferServo_in);
spindexer.shootAll();
TELE.addLine("starting to shoot");
} else if (!spindexer.shootAllComplete()) {
robot.transferServo.setPosition(transferServo_in); robot.transferServo.setPosition(transferServo_in);
TELE.addLine("shoot");
robot.spin1.setPower(-spinPow);
robot.spin2.setPower(spinPow);
} else { } else {
robot.transferServo.setPosition(transferServo_out); robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1; //spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
//spindexer.processIntake();
TELE.addLine("stop shooting");
}
shooterTicker++;
//spindexer.processIntake();
}
if (gamepad1.left_stick_button){
robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
shootAll = false; shootAll = false;
robot.transferServo.setPosition(transferServo_out);
spindexer.resetSpindexer(); spindexer.resetSpindexer();
spindexer.processIntake(); spindexer.processIntake();
} }
} }
}
// //
// if (shootAll) { // if (shootAll) {
@@ -832,29 +875,41 @@ public class TeleopV3 extends LinearOpMode {
hub.clearBulkCache(); hub.clearBulkCache();
} }
// //
TELE.addData("Spin1Green", green1 + ": " + ballIn(1)); // TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
TELE.addData("Spin2Green", green2 + ": " + ballIn(2)); // TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
TELE.addData("Spin3Green", green3 + ": " + ballIn(3)); // TELE.addData("Spin3Green", green3 + ": " + ballIn(3));
//
TELE.addData("pose", drive.localizer.getPose()); // TELE.addData("pose", drive.localizer.getPose());
TELE.addData("heading", drive.localizer.getPose().heading.toDouble()); // TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
TELE.addData("distanceToGoal", distanceToGoal); // TELE.addData("distanceToGoal", distanceToGoal);
TELE.addData("hood", robot.hood.getPosition()); // TELE.addData("hood", robot.hood.getPosition());
TELE.addData("targetVel", vel); // TELE.addData("targetVel", vel);
TELE.addData("Velocity", flywheel.getVelo()); // TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("shootOrder", shootOrder); // TELE.addData("Velo1", flywheel.velo1);
TELE.addData("oddColor", oddBallColor); // TELE.addData("Velo2", flywheel.velo2);
// TELE.addData("shootOrder", shootOrder);
// TELE.addData("oddColor", oddBallColor);
//
// // Spindexer Debug
TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1)); TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1));
TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition); TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition);
TELE.addData("spinIntakeState", spindexer.currentIntakeState); TELE.addData("spinIntakeState", spindexer.currentIntakeState);
TELE.addData("spinTestCounter", spindexer.counter); TELE.addData("spinTestCounter", spindexer.counter);
TELE.addData("autoSpintake", autoSpintake); TELE.addData("autoSpintake", autoSpintake);
TELE.addData("distanceRearCenter", spindexer.distanceRearCenter); //
TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver); // TELE.addData("shootall commanded", shootAll);
TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger); // // Targeting Debug
TELE.addData("shootall commanded", shootAll); // TELE.addData("robotX", robotX);
TELE.addData("timeSinceStamp", getRuntime() - shootStamp); // TELE.addData("robotY", robotY);
// TELE.addData("robotInchesX", targeting.robotInchesX);
// TELE.addData( "robotInchesY", targeting.robotInchesY);
// TELE.addData("Targeting Interpolate", turretInterpolate);
TELE.addData("Targeting GridX", targeting.robotGridX);
TELE.addData("Targeting GridY", targeting.robotGridY);
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
TELE.update(); TELE.update();
ticker++; ticker++;

View File

@@ -1,5 +1,7 @@
package org.firstinspires.ftc.teamcode.tests; package org.firstinspires.ftc.teamcode.tests;
import static org.firstinspires.ftc.teamcode.constants.Color.colorFilterAlpha;
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;
@@ -18,6 +20,9 @@ public class ColorTest extends LinearOpMode {
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());
double color1Distance = 0;
double color2Distance = 0;
double color3Distance = 0;
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
@@ -26,28 +31,34 @@ public class ColorTest extends LinearOpMode {
double green1 = robot.color1.getNormalizedColors().green; double green1 = robot.color1.getNormalizedColors().green;
double blue1 = robot.color1.getNormalizedColors().blue; double blue1 = robot.color1.getNormalizedColors().blue;
double red1 = robot.color1.getNormalizedColors().red; double red1 = robot.color1.getNormalizedColors().red;
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor()); TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1)); TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM)); TELE.addData("Color1 distance (mm)", color1Distance);
// ----- COLOR 2 ----- // ----- COLOR 2 -----
double green2 = robot.color2.getNormalizedColors().green; double green2 = robot.color2.getNormalizedColors().green;
double blue2 = robot.color2.getNormalizedColors().blue; double blue2 = robot.color2.getNormalizedColors().blue;
double red2 = robot.color2.getNormalizedColors().red; double red2 = robot.color2.getNormalizedColors().red;
double dist2 = robot.color2.getDistance(DistanceUnit.MM);
color2Distance = (colorFilterAlpha * dist2) + ((1-colorFilterAlpha) * color2Distance);
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor()); TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2)); TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM)); TELE.addData("Color2 distance (mm)", color2Distance);
// ----- COLOR 3 ----- // ----- COLOR 3 -----
double green3 = robot.color3.getNormalizedColors().green; double green3 = robot.color3.getNormalizedColors().green;
double blue3 = robot.color3.getNormalizedColors().blue; double blue3 = robot.color3.getNormalizedColors().blue;
double red3 = robot.color3.getNormalizedColors().red; double red3 = robot.color3.getNormalizedColors().red;
double dist3 = robot.color3.getDistance(DistanceUnit.MM);
color3Distance = (colorFilterAlpha * dist3) + ((1-colorFilterAlpha) * color3Distance);
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor()); TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3)); TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM)); TELE.addData("Color3 distance (mm)", color3Distance);
TELE.update(); TELE.update();
} }

View File

@@ -16,8 +16,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.List; import java.util.List;
@Config
@TeleOp
public class IntakeTest extends LinearOpMode { public class IntakeTest extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;
@@ -72,19 +71,19 @@ public class IntakeTest extends LinearOpMode {
initPos = currentPos; initPos = currentPos;
} }
if (reverse){ if (reverse){
robot.spin1.setPower(manualPow); robot.spin1.setPosition(manualPow);
robot.spin2.setPower(-manualPow); robot.spin2.setPosition(-manualPow);
} else { } else {
robot.spin1.setPower(-manualPow); robot.spin1.setPosition(-manualPow);
robot.spin2.setPower(manualPow); robot.spin2.setPosition(manualPow);
} }
robot.intake.setPower(1); robot.intake.setPower(1);
stamp = getRuntime(); stamp = getRuntime();
TELE.addData("Reverse?", reverse); TELE.addData("Reverse?", reverse);
TELE.update(); TELE.update();
} else { } else {
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
if (getRuntime() - stamp < 1) { if (getRuntime() - stamp < 1) {
robot.intake.setPower(-(getRuntime() - stamp)*2); robot.intake.setPower(-(getRuntime() - stamp)*2);
@@ -191,15 +190,15 @@ public class IntakeTest extends LinearOpMode {
if (!atTarget) { if (!atTarget) {
powPID = servo.setSpinPos(spindexerPos); powPID = servo.setSpinPos(spindexerPos);
robot.spin1.setPower(powPID); robot.spin1.setPosition(powPID);
robot.spin2.setPower(-powPID); robot.spin2.setPosition(-powPID);
steadySpin = false; steadySpin = false;
wasMoving = true; // remember we were moving wasMoving = true; // remember we were moving
stamp = getRuntime(); stamp = getRuntime();
} else { } else {
robot.spin1.setPower(0); robot.spin1.setPosition(0);
robot.spin2.setPower(0); robot.spin2.setPosition(0);
steadySpin = true; steadySpin = true;
wasMoving = false; wasMoving = false;
} }

View File

@@ -4,32 +4,35 @@ 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;
import com.qualcomm.hardware.limelightvision.LLResult; 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.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import java.util.List; import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config @Config
@TeleOp @TeleOp
//TODO: fix to get the apriltag that it is reading //TODO: fix to get the apriltag that it is reading
public class LimelightTest extends LinearOpMode { public class LimelightTest extends LinearOpMode {
MultipleTelemetry TELE; MultipleTelemetry TELE;
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track Turret turret;
Robot robot;
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 4 is for red track; DO NOT USE 3
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
public static boolean turretMode = false;
public static double turretPos = 0.501;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "limelight");
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
limelight.pipelineSwitch(pipeline); robot = new Robot(hardwareMap);
turret = new Turret(robot, TELE, robot.limelight);
robot.limelight.pipelineSwitch(pipeline);
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
limelight.start();
while (opModeIsActive()){ while (opModeIsActive()){
if (mode == 0){ if (mode == 0){
limelight.pipelineSwitch(pipeline); robot.limelight.pipelineSwitch(pipeline);
LLResult result = limelight.getLatestResult(); LLResult result = robot.limelight.getLatestResult();
if (result != null) { if (result != null) {
if (result.isValid()) { if (result.isValid()) {
TELE.addData("tx", result.getTx()); TELE.addData("tx", result.getTx());
@@ -38,40 +41,29 @@ public class LimelightTest extends LinearOpMode {
} }
} }
} else if (mode == 1){ } else if (mode == 1){
limelight.pipelineSwitch(1); int obeliskID = turret.detectObelisk();
LLResult result = limelight.getLatestResult(); TELE.addData("Limelight ID", obeliskID);
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(); TELE.update();
} else if (mode == 2 || mode == 3){ // Use redAlliance variable to switch between red and blue
double tx = turret.getBearing();
double ty = turret.getTy();
double x = turret.getLimelightX();
double y = turret.getLimelightY();
TELE.addData("tx", tx);
TELE.addData("ty", ty);
TELE.addData("x", x);
TELE.addData("y", y);
TELE.update();
} else {
robot.limelight.pipelineSwitch(0);
}
if (turretMode){
if (turretPos != 0.501){
turret.manualSetTurret(turretPos);
}
} }
} }
} 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);
}
}
} }
} }

View File

@@ -9,8 +9,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
@TeleOp
@Config
public class PIDServoTest extends LinearOpMode { public class PIDServoTest extends LinearOpMode {
public static double p = 2, i = 0, d = 0, f = 0; public static double p = 2, i = 0, d = 0, f = 0;
@@ -47,12 +45,11 @@ public class PIDServoTest extends LinearOpMode {
double pid = controller.calculate(pos, target); double pid = controller.calculate(pos, target);
robot.spin1.setPower(pid); robot.spin1.setPosition(pid);
robot.spin2.setPower(-pid); robot.spin2.setPosition(-pid);
} }
telemetry.addData("pos", pos); telemetry.addData("pos", pos);
telemetry.addData("Turret Voltage", robot.turr1Pos.getCurrentPosition());
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage()); telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
telemetry.addData("target", target); telemetry.addData("target", target);
telemetry.addData("Mode", mode); telemetry.addData("Mode", mode);

View File

@@ -1,6 +1,11 @@
package org.firstinspires.ftc.teamcode.tests; package org.firstinspires.ftc.teamcode.tests;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinSpeedIncrease;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -11,27 +16,42 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
import org.firstinspires.ftc.teamcode.utils.Flywheel; 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.teamcode.utils.Spindexer;
@Config @Config
@TeleOp @TeleOp
public class ShooterTest extends LinearOpMode { public class ShooterTest extends LinearOpMode {
public static int mode = 1;
public static int mode = 0;
public static double parameter = 0.0; public static double parameter = 0.0;
// --- CONSTANTS YOU TUNE --- // --- CONSTANTS YOU TUNE ---
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED //TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
public static double Velocity = 0.0; public static double Velocity = 0.0;
public static double P = 40.0; public static double P = 255.0;
public static double I = 0.3; public static double I = 0.0;
public static double D = 7.0; public static double D = 0.0;
public static double F = 10.0; public static double F = 7.5;
public static double transferPower = 1.0; public static double transferPower = 1.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; public static boolean shoot = false;
public static boolean intake = false;
Robot robot; Robot robot;
Flywheel flywheel; Flywheel flywheel;
Servos servo;
double shootStamp = 0.0;
boolean shootAll = false;
public double spinPow = 0.09;
public static boolean enableHoodAutoOpen = false;
public double hoodAdjust = 0.0;
public static double hoodAdjustFactor = 1.0;
private int shooterTicker = 0;
Spindexer spindexer ;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
@@ -40,6 +60,8 @@ public class ShooterTest extends LinearOpMode {
DcMotorEx leftShooter = robot.shooter1; DcMotorEx leftShooter = robot.shooter1;
DcMotorEx rightShooter = robot.shooter2; DcMotorEx rightShooter = robot.shooter2;
flywheel = new Flywheel(hardwareMap); flywheel = new Flywheel(hardwareMap);
spindexer = new Spindexer(hardwareMap);
servo = new Servos(hardwareMap);
MultipleTelemetry TELE = new MultipleTelemetry( MultipleTelemetry TELE = new MultipleTelemetry(
telemetry, FtcDashboard.getInstance().getTelemetry() telemetry, FtcDashboard.getInstance().getTelemetry()
@@ -55,21 +77,73 @@ public class ShooterTest extends LinearOpMode {
rightShooter.setPower(parameter); rightShooter.setPower(parameter);
leftShooter.setPower(parameter); leftShooter.setPower(parameter);
} else if (mode == 1) { } else if (mode == 1) {
flywheel.setPIDF(P,I,D,F); flywheel.setPIDF(P, I, D, F);
flywheel.manageFlywheel((int) Velocity); flywheel.manageFlywheel((int) Velocity);
} }
if (hoodPos != 0.501) { if (hoodPos != 0.501) {
if (enableHoodAutoOpen) {
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
} else {
robot.hood.setPosition(hoodPos); robot.hood.setPosition(hoodPos);
} }
}
if (intake) {
robot.intake.setPower(1);
} else {
robot.intake.setPower(0);
}
robot.transfer.setPower(transferPower);
if (shoot) { if (shoot) {
shootStamp = getRuntime();
shootAll = true;
shoot = false;
robot.transfer.setPower(transferPower);
shooterTicker = 0;
}
if (shootAll) {
//intake = false;
//reject = false;
// TODO: Change starting position based on desired order to shoot green ball
//spindexPos = spindexer_intakePos1;
if (getRuntime() - shootStamp < 3.5) {
if (shooterTicker == 0 && !servo.spinEqual(spinStartPos)){
robot.spin1.setPosition(spinStartPos);
robot.spin2.setPosition(1-spinStartPos);
} else {
robot.transferServo.setPosition(transferServo_in); robot.transferServo.setPosition(transferServo_in);
shooterTicker++;
double prevSpinPos = robot.spin1.getPosition();
robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease);
robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease);
}
} else { } else {
robot.transferServo.setPosition(transferServo_out); robot.transferServo.setPosition(transferServo_out);
//spindexPos = spindexer_intakePos1;
shootAll = false;
shooterTicker = 0;
robot.transferServo.setPosition(transferServo_out);
robot.transfer.setPower(0);
spindexer.resetSpindexer();
spindexer.processIntake();
} }
} else {
spindexer.processIntake();
}
TELE.addData("Velocity", flywheel.getVelo()); TELE.addData("Velocity", flywheel.getVelo());
TELE.addData("Velocity 1", flywheel.getVelo1()); TELE.addData("Velocity 1", flywheel.getVelo1());
TELE.addData("Velocity 2", flywheel.getVelo2()); TELE.addData("Velocity 2", flywheel.getVelo2());

View File

@@ -0,0 +1,50 @@
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.acmerobotics.roadrunner.Pose2d;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Autonomous
@Config
public class TurretTest extends LinearOpMode {
public static boolean zeroTurr = false;
@Override
public void runOpMode() throws InterruptedException {
Robot robot = new Robot(hardwareMap);
MultipleTelemetry TELE = new MultipleTelemetry(
telemetry, FtcDashboard.getInstance().getTelemetry()
);
Turret turret = new Turret(robot, TELE, robot.limelight);
waitForStart();
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
while(opModeIsActive()){
drive.updatePoseEstimate();
turret.trackGoal(drive.localizer.getPose());
TELE.addData("tpos", turret.getTurrPos());
TELE.addData("Limelight tx", turret.getBearing());
TELE.addData("Limelight ty", turret.getTy());
TELE.addData("Limelight X", turret.getLimelightX());
TELE.addData("Limelight Y", turret.getLimelightY());
if(zeroTurr){
turret.zeroTurretEncoder();
}
TELE.update();
}
}
}

View File

@@ -1,30 +1,25 @@
package org.firstinspires.ftc.teamcode.utils; package org.firstinspires.ftc.teamcode.utils;
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
import com.arcrobotics.ftclib.controller.PIDFController;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.qualcomm.robotcore.hardware.PIDFCoefficients;
public class Flywheel { public class Flywheel {
Robot robot; Robot robot;
MultipleTelemetry TELE; public PIDFCoefficients shooterPIDF1, shooterPIDF2;
double initPos = 0.0;
double stamp = 0.0;
double stamp1 = 0.0;
double ticker = 0.0;
double currentPos = 0.0;
double velo = 0.0; double velo = 0.0;
double velo1 = 0.0; public double velo1 = 0.0;
double velo2 = 0.0; public double velo2 = 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 (HardwareMap hardwareMap) { public Flywheel (HardwareMap hardwareMap) {
robot = new Robot(hardwareMap); robot = new Robot(hardwareMap);
shooterPIDF1 = new PIDFCoefficients
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
shooterPIDF2 = new PIDFCoefficients
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
} }
public double getVelo () { public double getVelo () {
@@ -43,14 +38,14 @@ public class Flywheel {
// Set the robot PIDF for the next cycle. // Set the robot PIDF for the next cycle.
public void setPIDF(double p, double i, double d, double f) { public void setPIDF(double p, double i, double d, double f) {
robot.shooterPIDF.p = p; shooterPIDF1.p = p;
robot.shooterPIDF.i = i; shooterPIDF1.i = i;
robot.shooterPIDF.d = d; shooterPIDF1.d = d;
robot.shooterPIDF.f = f; shooterPIDF1.f = f;
} shooterPIDF2.p = p;
private double getTimeSeconds () shooterPIDF2.i = i;
{ shooterPIDF2.d = d;
return (double) System.currentTimeMillis()/1000.0; shooterPIDF2.f = f;
} }
// Convert from RPM to Ticks per Second // Convert from RPM to Ticks per Second
@@ -62,19 +57,16 @@ public class Flywheel {
public double manageFlywheel(double commandedVelocity) { public double manageFlywheel(double commandedVelocity) {
targetVelocity = commandedVelocity; targetVelocity = commandedVelocity;
// Turn PIDF for Target Velocities // Add code here to set PIDF based on desired RPM
//robot.shooterPIDF.p = P;
//robot.shooterPIDF.i = I; robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
//robot.shooterPIDF.d = D; robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
//robot.shooterPIDF.f = F;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity)); robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity)); robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
// Record Current Velocity // Record Current Velocity
velo1 = TPS_to_RPM(robot.shooter1.getVelocity()); velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
velo2 = TPS_to_RPM(robot.shooter1.getVelocity()); // Possible error: should it be shooter2 not shooter1? velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = Math.max(velo1,velo2); velo = Math.max(velo1,velo2);
// really should be a running average of the last 5 // really should be a running average of the last 5

View File

@@ -8,6 +8,8 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
@TeleOp @TeleOp
@Config @Config
public class PositionalServoProgrammer extends LinearOpMode { public class PositionalServoProgrammer extends LinearOpMode {
@@ -16,33 +18,26 @@ public class PositionalServoProgrammer extends LinearOpMode {
Servos servo; 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 light = 0.501;
Turret turret;
@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); servo = new Servos(hardwareMap);
turret = new Turret(robot, TELE, robot.limelight );
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 && !servo.spinEqual(spindexPos)){
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){ if (turretPos != 0.501){
robot.turr1.setPosition(turretPos); robot.turr1.setPosition(turretPos);
@@ -54,6 +49,9 @@ public class PositionalServoProgrammer extends LinearOpMode {
if (hoodPos != 0.501){ if (hoodPos != 0.501){
robot.hood.setPosition(hoodPos); robot.hood.setPosition(hoodPos);
} }
if (light !=0.501){
robot.light.setPosition(light);
}
// To check configuration of spindexer: // To check configuration of spindexer:
// Set "mode" to 1 and spindexPow to 0.1 // Set "mode" to 1 and spindexPow to 0.1
// If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE // If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE
@@ -66,13 +64,12 @@ public class PositionalServoProgrammer extends LinearOpMode {
//TODO: @KeshavAnandCode do the above please //TODO: @KeshavAnandCode do the above please
TELE.addData("spindexer pos", servo.getSpinPos()); TELE.addData("spindexer pos", servo.getSpinPos());
TELE.addData("turret pos", servo.getTurrPos()); TELE.addData("turret pos", robot.turr1.getPosition());
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage()); TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage()); TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
TELE.addData("hood pos", robot.hood.getPosition()); TELE.addData("hood pos", robot.hood.getPosition());
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage()); TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
TELE.addData("turret voltage", robot.turr1Pos.getCurrentPosition()); TELE.addData("tpos ", turret.getTurrPos() );
TELE.addData("spindexer pow", robot.spin1.getPower());
TELE.update(); TELE.update();
} }
} }

View File

@@ -1,5 +1,7 @@
package org.firstinspires.ftc.teamcode.utils; package org.firstinspires.ftc.teamcode.utils;
import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.hardware.ServoEx;
import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.hardware.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;
@@ -14,10 +16,13 @@ import com.qualcomm.robotcore.hardware.Servo;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
@Config
public class Robot { public class Robot {
//Initialize Public Components //Initialize Public Components
public static boolean usingLimelight = true;
public static boolean usingCamera = false;
public DcMotorEx frontLeft; public DcMotorEx frontLeft;
public DcMotorEx frontRight; public DcMotorEx frontRight;
public DcMotorEx backLeft; public DcMotorEx backLeft;
@@ -25,23 +30,24 @@ public class Robot {
public DcMotorEx intake; public DcMotorEx intake;
public DcMotorEx transfer; public DcMotorEx transfer;
public PIDFCoefficients shooterPIDF; public PIDFCoefficients shooterPIDF;
public double shooterPIDF_P = 10.0; public double shooterPIDF_P = 255.0;
public double shooterPIDF_I = 0.6; public double shooterPIDF_I = 0.0;
public double shooterPIDF_D = 5.0; public double shooterPIDF_D = 0.0;
public double shooterPIDF_F = 10.0; public double shooterPIDF_F = 7.5;
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public double[] shooterPIDF_StepSizes = {10.0,1.0,0.001, 0.0001};
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 turr1; public Servo turr1;
public Servo turr2; public Servo turr2;
public CRServo spin1;
public CRServo spin2; public Servo spin1;
public Servo spin2;
public AnalogInput spin1Pos; public AnalogInput spin1Pos;
public AnalogInput spin2Pos; public AnalogInput spin2Pos;
public DcMotorEx turr1Pos; public AnalogInput turr1Pos;
public AnalogInput transferServoPos; public AnalogInput transferServoPos;
public AprilTagProcessor aprilTagProcessor; public AprilTagProcessor aprilTagProcessor;
public WebcamName webcam; public WebcamName webcam;
@@ -49,10 +55,7 @@ public class Robot {
public RevColorSensorV3 color2; public RevColorSensorV3 color2;
public RevColorSensorV3 color3; public RevColorSensorV3 color3;
public Limelight3A limelight; public Limelight3A limelight;
public Servo light;
public static boolean usingLimelight = true;
public static boolean usingCamera = true;
public Robot(HardwareMap hardwareMap) { public Robot(HardwareMap hardwareMap) {
@@ -77,11 +80,13 @@ public class Robot {
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2"); shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode //TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
shooter1.setDirection(DcMotorSimple.Direction.REVERSE); shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
shooterPIDF = new PIDFCoefficients(shooterPIDF_P,shooterPIDF_I , shooterPIDF_D, shooterPIDF_F); shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F);
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER); shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter1.setVelocity(0);
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER); shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter2.setVelocity(0);
hood = hardwareMap.get(Servo.class, "hood"); hood = hardwareMap.get(Servo.class, "hood");
@@ -89,20 +94,17 @@ public class Robot {
turr2 = hardwareMap.get(Servo.class, "t2"); turr2 = hardwareMap.get(Servo.class, "t2");
turr1Pos = intake; // Encoder of turret plugged in intake port turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer //TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
spin1 = hardwareMap.get(CRServo.class, "spin1"); spin1 = hardwareMap.get(Servo.class, "spin2");
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos"); spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
spin2 = hardwareMap.get(CRServo.class, "spin2"); spin2 = hardwareMap.get(Servo.class, "spin1");
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos"); spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
transfer = hardwareMap.get(DcMotorEx.class, "transfer"); transfer = hardwareMap.get(DcMotorEx.class, "transfer");
transferServo = hardwareMap.get(Servo.class, "transferServo"); transferServo = hardwareMap.get(Servo.class, "transferServo");
@@ -118,11 +120,13 @@ public class Robot {
color3 = hardwareMap.get(RevColorSensorV3.class, "c3"); color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
if (usingLimelight){ if (usingLimelight) {
limelight = hardwareMap.get(Limelight3A.class, "limelight"); limelight = hardwareMap.get(Limelight3A.class, "limelight");
} else if (usingCamera){ } else if (usingCamera) {
webcam = hardwareMap.get(WebcamName.class, "Webcam 1"); webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults(); aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
} }
light = hardwareMap.get(Servo.class, "light");
} }
} }

View File

@@ -8,10 +8,10 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
public class Servos { public class Servos {
//PID constants //PID constants
// TODO: get PIDF constants // TODO: get PIDF constants
public static double spinP = 3.3, spinI = 0, spinD = 0.1, spinF = 0.02; public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0; public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
public static double spin_scalar = 1.0086; public static double spin_scalar = 1.112;
public static double spin_restPos = 0.0; public static double spin_restPos = 0.155;
public static double turret_scalar = 1.009; public static double turret_scalar = 1.009;
public static double turret_restPos = 0.0; public static double turret_restPos = 0.0;
Robot robot; Robot robot;
@@ -27,34 +27,29 @@ public class Servos {
} }
// In the code below, encoder = robot.servo.getVoltage() // In the code below, encoder = robot.servo.getVoltage()
// TODO: set the restPos and scalar
public double getSpinPos() { public double getSpinPos() {
return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3); 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) { public double setSpinPos(double pos) {
spinPID.setPIDF(spinP, spinI, spinD, spinF);
return spinPID.calculate(this.getSpinPos(), pos); return pos;
} }
public boolean spinEqual(double pos) { public boolean spinEqual(double pos) {
return Math.abs(pos - this.getSpinPos()) < 0.02; return Math.abs(pos - this.getSpinPos()) < 0.03;
} }
public double getTurrPos() { public double getTurrPos() {
return (double) ((double) robot.turr1Pos.getCurrentPosition() / 1024.0) * ((double) 44.0 / (double) 77.0); return 1.0;
} }
public double setTurrPos(double pos) { public double setTurrPos(double pos) {
turretPID.setPIDF(turrP, turrI, turrD, turrF); return 1.0;
return spinPID.calculate(this.getTurrPos(), pos);
} }
public boolean turretEqual(double pos) { public boolean turretEqual(double pos) {
return Math.abs(pos - this.getTurrPos()) < 0.01; return true;
} }
} }

View File

@@ -4,6 +4,7 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.arcrobotics.ftclib.controller.PIDFController; import com.arcrobotics.ftclib.controller.PIDFController;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
import static org.firstinspires.ftc.teamcode.constants.Color.*;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
@@ -16,9 +17,11 @@ import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP; import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.constants.Types;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
public class Spindexer { public class Spindexer {
Robot robot; Robot robot;
Servos servos; Servos servos;
Flywheel flywheel; Flywheel flywheel;
@@ -36,6 +39,12 @@ public class Spindexer {
public double distanceFrontDriver = 0.0; public double distanceFrontDriver = 0.0;
public double distanceFrontPassenger = 0.0; public double distanceFrontPassenger = 0.0;
public double spindexerWiggle = 0.01;
public double spindexerOuttakeWiggle = 0.01;
private double prevPos = 0.0;
public double spindexerPosOffset = 0.00;
public Types.Motif desiredMotif = Types.Motif.NONE;
// For Use // For Use
enum RotatedBallPositionNames { enum RotatedBallPositionNames {
REARCENTER, REARCENTER,
@@ -52,7 +61,9 @@ public class Spindexer {
} }
enum IntakeState { enum IntakeState {
UNKNOWN, UNKNOWN_START,
UNKNOWN_MOVE,
UNKNOWN_DETECT,
INTAKE, INTAKE,
FINDNEXT, FINDNEXT,
MOVING, MOVING,
@@ -60,15 +71,20 @@ public class Spindexer {
SHOOTNEXT, SHOOTNEXT,
SHOOTMOVING, SHOOTMOVING,
SHOOTWAIT, SHOOTWAIT,
}; SHOOT_ALL_PREP,
SHOOT_ALL_READY
}
public IntakeState currentIntakeState = IntakeState.UNKNOWN; int shootWaitCount = 0;
enum BallColor { public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
public IntakeState prevIntakeState = IntakeState.UNKNOWN_START;
public int unknownColorDetect = 0;
public enum BallColor {
UNKNOWN, UNKNOWN,
GREEN, GREEN,
PURPLE PURPLE
}; }
class BallPosition { class BallPosition {
boolean isEmpty = true; boolean isEmpty = true;
@@ -99,7 +115,9 @@ public class Spindexer {
double[] outakePositions = double[] outakePositions =
{spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3}; {spindexer_outtakeBall1+spindexerPosOffset,
spindexer_outtakeBall2+spindexerPosOffset,
spindexer_outtakeBall3+spindexerPosOffset};
double[] intakePositions = double[] intakePositions =
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3}; {spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
@@ -131,28 +149,32 @@ public class Spindexer {
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
resetBallPosition(i); resetBallPosition(i);
} }
currentIntakeState = IntakeState.UNKNOWN; currentIntakeState = IntakeState.UNKNOWN_START;
} }
// Detects if a ball is found and what color. // Detects if a ball is found and what color.
// Returns true is there was a new ball found in Position 1 // Returns true is there was a new ball found in Position 1
// FIXIT: Reduce number of times that we read the color sensors for loop times. // FIXIT: Reduce number of times that we read the color sensors for loop times.
public boolean detectBalls() { public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
boolean newPos1Detection = false; boolean newPos1Detection = false;
int spindexerBallPos = 0; int spindexerBallPos = 0;
// Read Distances // Read Distances
distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM); double dRearCenter = robot.color1.getDistance(DistanceUnit.MM);
distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM); distanceRearCenter = (colorFilterAlpha * dRearCenter) + ((1-colorFilterAlpha) * distanceRearCenter);
distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM); double dFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
distanceFrontDriver = (colorFilterAlpha * dFrontDriver) + ((1-colorFilterAlpha) * distanceFrontDriver);
double dFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
// Position 1 // Position 1
if (distanceRearCenter < 43) { if (distanceRearCenter < 60) {
// Mark Ball Found // Mark Ball Found
newPos1Detection = true; newPos1Detection = true;
if (detectRearColor) {
// Detect which color // Detect which color
double green = robot.color1.getNormalizedColors().green; double green = robot.color1.getNormalizedColors().green;
double red = robot.color1.getNormalizedColors().red; double red = robot.color1.getNormalizedColors().red;
@@ -161,30 +183,32 @@ public class Spindexer {
double gP = green / (green + red + blue); double gP = green / (green + red + blue);
// FIXIT - Add filtering to improve accuracy. // FIXIT - Add filtering to improve accuracy.
if (gP >= 0.4) { if (gP >= 0.38) {
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // green
} else { } else {
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
}
} }
} }
// Position 2 // Position 2
// Find which ball position this is in the spindexer // Find which ball position this is in the spindexer
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()]; spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
if (distanceFrontDriver < 60) { if (distanceFrontDriver < 50) {
// reset FoundEmpty because looking for 3 in a row before reset // reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0; ballPositions[spindexerBallPos].foundEmpty = 0;
// FIXIT: Comment out for now due to loop time concerns if (detectFrontColor) {
// double green = robot.color2.getNormalizedColors().green; double green = robot.color2.getNormalizedColors().green;
// double red = robot.color2.getNormalizedColors().red; double red = robot.color2.getNormalizedColors().red;
// double blue = robot.color2.getNormalizedColors().blue; double blue = robot.color2.getNormalizedColors().blue;
//
// double gP = green / (green + red + blue);
// if (gP >= 0.4) { double gP = green / (green + red + blue);
// b2 = 2; // purple
// } else { if (gP >= 0.4) {
// b2 = 1; // green ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
// } } else {
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
}
}
} else { } else {
if (!ballPositions[spindexerBallPos].isEmpty) { if (!ballPositions[spindexerBallPos].isEmpty) {
if (ballPositions[spindexerBallPos].foundEmpty > 3) { if (ballPositions[spindexerBallPos].foundEmpty > 3) {
@@ -197,22 +221,23 @@ public class Spindexer {
// Position 3 // Position 3
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()]; spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
if (distanceFrontPassenger < 33) { if (distanceFrontPassenger < 29) {
// reset FoundEmpty because looking for 3 in a row before reset // reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0; ballPositions[spindexerBallPos].foundEmpty = 0;
// FIXIT: Comment out for now due to loop time concerns if (detectFrontColor) {
// double green = robot.color3.getNormalizedColors().green; double green = robot.color3.getNormalizedColors().green;
// double red = robot.color3.getNormalizedColors().red; double red = robot.color3.getNormalizedColors().red;
// double blue = robot.color3.getNormalizedColors().blue; double blue = robot.color3.getNormalizedColors().blue;
// double gP = green / (green + red + blue); double gP = green / (green + red + blue);
// if (gP >= 0.4) { if (gP >= 0.42) {
// b3 = 2; // purple ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
// } else { } else {
// b3 = 1; // green ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
// } }
}
} else { } else {
if (!ballPositions[spindexerBallPos].isEmpty) { if (!ballPositions[spindexerBallPos].isEmpty) {
if (ballPositions[spindexerBallPos].foundEmpty > 3) { if (ballPositions[spindexerBallPos].foundEmpty > 3) {
@@ -234,19 +259,51 @@ public class Spindexer {
return newPos1Detection; return newPos1Detection;
} }
// Has code to unjam spindexer
public void moveSpindexerToPos(double pos) { private void moveSpindexerToPos(double pos) {
spinCurrentPos = servos.getSpinPos(); robot.spin1.setPosition(pos);
robot.spin2.setPosition(1-pos);
double spindexPID = spinPID.calculate(spinCurrentPos, pos); double currentPos = servos.getSpinPos();
if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){
robot.spin1.setPower(spindexPID); // if (currentPos > pos){
robot.spin2.setPower(-spindexPID); // robot.spin1.setPosition(servos.getSpinPos() + 0.05);
// robot.spin2.setPosition(1 - servos.getSpinPos() - 0.05);
// } else {
// robot.spin1.setPosition(servos.getSpinPos() - 0.05);
// robot.spin2.setPosition(1 - servos.getSpinPos() + 0.05);
// }
}
prevPos = currentPos;
} }
public void stopSpindexer() { public void stopSpindexer() {
robot.spin1.setPower(0);
robot.spin2.setPower(0); }
public void ballCounterLight(){
int counter = 0;
if (!ballPositions[0].isEmpty){
counter++;
}
if (!ballPositions[1].isEmpty){
counter++;
}
if (!ballPositions[2].isEmpty){
counter++;
}
if (counter == 3){
robot.light.setPosition(Light3);
} else if (counter == 2){
robot.light.setPosition(Light2);
} else if (counter == 1){
robot.light.setPosition(Light1);
} else {
robot.light.setPosition(Light0);
}
}
public boolean slotIsEmpty(int slot){
return !ballPositions[slot].isEmpty;
} }
public boolean isFull () { public boolean isFull () {
@@ -255,20 +312,40 @@ public class Spindexer {
public boolean processIntake() { public boolean processIntake() {
switch (currentIntakeState) { switch (currentIntakeState) {
case UNKNOWN: case UNKNOWN_START:
// For now just set position ONE if UNKNOWN // For now just set position ONE if UNKNOWN
commandedIntakePosition = 0; commandedIntakePosition = 0;
servos.setSpinPos(intakePositions[0]); moveSpindexerToPos(intakePositions[0]);
currentIntakeState = Spindexer.IntakeState.MOVING; currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
break;
case UNKNOWN_MOVE:
// Stopping when we get to the new position
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
stopSpindexer();
unknownColorDetect = 0;
} else {
// Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
}
break;
case UNKNOWN_DETECT:
if (unknownColorDetect >5) {
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
} else {
//detectBalls(true, true);
unknownColorDetect++;
}
break; break;
case INTAKE: case INTAKE:
// Ready for intake and Detecting a New Ball // Ready for intake and Detecting a New Ball
if (detectBalls()) { if (detectBalls(true, false)) {
ballPositions[commandedIntakePosition].isEmpty = false; ballPositions[commandedIntakePosition].isEmpty = false;
currentIntakeState = Spindexer.IntakeState.FINDNEXT; currentIntakeState = Spindexer.IntakeState.FINDNEXT;
} else { } else {
// Maintain Position // Maintain Position
moveSpindexerToPos(intakePositions[commandedIntakePosition]); spindexerWiggle *= -1.0;
moveSpindexerToPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
} }
break; break;
case FINDNEXT: case FINDNEXT:
@@ -276,31 +353,28 @@ public class Spindexer {
double currentSpindexerPos = servos.getSpinPos(); double currentSpindexerPos = servos.getSpinPos();
double commandedtravelDistance = 2.0; double commandedtravelDistance = 2.0;
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos); double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { //if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
if (ballPositions[0].isEmpty) {
// Position 1 // Position 1
commandedIntakePosition = 0; commandedIntakePosition = 0;
servos.setSpinPos(intakePositions[commandedIntakePosition]);
currentIntakeState = Spindexer.IntakeState.MOVING; currentIntakeState = Spindexer.IntakeState.MOVING;
commandedtravelDistance = proposedTravelDistance;
} }
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos); proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { //if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
if (ballPositions[1].isEmpty) {
// Position 2 // Position 2
commandedIntakePosition = 1; commandedIntakePosition = 1;
servos.setSpinPos(intakePositions[commandedIntakePosition]);
currentIntakeState = Spindexer.IntakeState.MOVING; currentIntakeState = Spindexer.IntakeState.MOVING;
commandedtravelDistance = proposedTravelDistance;
} }
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos); proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { if (ballPositions[2].isEmpty) {
// Position 3 // Position 3
commandedIntakePosition = 2; commandedIntakePosition = 2;
servos.setSpinPos(intakePositions[commandedIntakePosition]);
currentIntakeState = Spindexer.IntakeState.MOVING; currentIntakeState = Spindexer.IntakeState.MOVING;
commandedtravelDistance = proposedTravelDistance;
} }
if (currentIntakeState != Spindexer.IntakeState.MOVING) { if (currentIntakeState != Spindexer.IntakeState.MOVING) {
// Full // Full
//commandedIntakePosition = bestFitMotif();
currentIntakeState = Spindexer.IntakeState.FULL; currentIntakeState = Spindexer.IntakeState.FULL;
} }
moveSpindexerToPos(intakePositions[commandedIntakePosition]); moveSpindexerToPos(intakePositions[commandedIntakePosition]);
@@ -311,7 +385,7 @@ public class Spindexer {
if (servos.spinEqual(intakePositions[commandedIntakePosition])) { if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.INTAKE; currentIntakeState = Spindexer.IntakeState.INTAKE;
stopSpindexer(); stopSpindexer();
detectBalls(); //detectBalls(false, false);
} else { } else {
// Keep moving the spindexer // Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]); moveSpindexerToPos(intakePositions[commandedIntakePosition]);
@@ -320,13 +394,35 @@ public class Spindexer {
case FULL: case FULL:
// Double Check Colors // Double Check Colors
detectBalls(); detectBalls(false, false); // Minimize hardware calls
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) { if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
// Error handling found an empty spot, get it ready for a ball // Error handling found an empty spot, get it ready for a ball
currentIntakeState = Spindexer.IntakeState.FINDNEXT; currentIntakeState = Spindexer.IntakeState.FINDNEXT;
} }
// Maintain Position // Maintain Position
moveSpindexerToPos(intakePositions[commandedIntakePosition]); spindexerWiggle *= -1.0;
moveSpindexerToPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
break;
case SHOOT_ALL_PREP:
// We get here with function call to prepareToShootMotif
// Stopping when we get to the new position
commandedIntakePosition = 0;
if (!servos.spinEqual(outakePositions[commandedIntakePosition])) {
// Keep moving the spindexer
moveSpindexerToPos(outakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
}
break;
case SHOOT_ALL_READY: // Not used
// Double Check Colors
//detectBalls(false, false); // Minimize hardware calls
if (ballPositions[0].isEmpty && ballPositions[1].isEmpty && ballPositions[2].isEmpty) {
// All ball shot move to intake state
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
}
// Maintain Position
moveSpindexerToPos(outakePositions[commandedIntakePosition]);
break; break;
case SHOOTNEXT: case SHOOTNEXT:
@@ -334,67 +430,148 @@ public class Spindexer {
if (!ballPositions[0].isEmpty) { if (!ballPositions[0].isEmpty) {
// Position 1 // Position 1
commandedIntakePosition = 0; commandedIntakePosition = 0;
servos.setSpinPos(outakePositions[commandedIntakePosition]);
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
} else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty? } else if (!ballPositions[1].isEmpty) {
// Position 2 // Position 2
commandedIntakePosition = 1; commandedIntakePosition = 1;
servos.setSpinPos(outakePositions[commandedIntakePosition]);
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
} else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty? } else if (!ballPositions[2].isEmpty) {
// Position 3 // Position 3
commandedIntakePosition = 2; commandedIntakePosition = 2;
servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
} else { } else {
// Empty return to intake state // Empty return to intake state
currentIntakeState = IntakeState.FINDNEXT; currentIntakeState = IntakeState.FINDNEXT;
} }
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" moveSpindexerToPos(outakePositions[commandedIntakePosition]);
break; break;
case SHOOTMOVING: case SHOOTMOVING:
// Stopping when we get to the new position // Stopping when we get to the new position
if (servos.spinEqual(outakePositions[commandedIntakePosition])) { if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT; currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
ballPositions[commandedIntakePosition].isEmpty = true;
// Advance to next full position and wait
// commandedIntakePosition++;
// if (commandedIntakePosition > 2) {
// commandedIntakePosition = 0;
// }
// // Continue moving to next position
// servos.setSpinPos(intakePositions[commandedIntakePosition]);
// currentIntakeState = Spindexer.IntakeState.MOVING;
} else { } else {
// Keep moving the spindexer // Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" moveSpindexerToPos(outakePositions[commandedIntakePosition]);
} }
break; break;
case SHOOTWAIT: case SHOOTWAIT:
double shootWaitMax = 4;
// Stopping when we get to the new position // Stopping when we get to the new position
if (servos.spinEqual(intakePositions[commandedIntakePosition])) { if (prevIntakeState != currentIntakeState) {
currentIntakeState = Spindexer.IntakeState.INTAKE; if (commandedIntakePosition==2) {
stopSpindexer(); shootWaitMax = 5;
detectBalls();
} else {
// Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
} }
shootWaitCount = 0;
} else {
shootWaitCount++;
}
// wait 10 cycles
if (shootWaitCount > shootWaitMax) {
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
ballPositions[commandedIntakePosition].isEmpty = true;
shootWaitCount = 0;
//stopSpindexer();
//detectBalls(true, false);
}
// Keep moving the spindexer
spindexerOuttakeWiggle *= -1.01;
moveSpindexerToPos(outakePositions[commandedIntakePosition]+spindexerOuttakeWiggle);
break; break;
default: default:
// Statements to execute if no case matches // Statements to execute if no case matches
} }
prevIntakeState = currentIntakeState;
//TELE.addData("commandedIntakePosition", commandedIntakePosition); //TELE.addData("commandedIntakePosition", commandedIntakePosition);
//TELE.update(); //TELE.update();
// Signal a successful intake // Signal a successful intake
return false; return false;
} }
public void setDesiredMotif (Types.Motif newMotif) {
desiredMotif = newMotif;
}
// Returns the best fit for the motiff
public int bestFitMotif () {
switch (desiredMotif) {
case GPP:
if (ballPositions[0].ballColor == BallColor.GREEN) {
return 2;
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
return 0;
} else {
return 1;
}
//break;
case PGP:
if (ballPositions[0].ballColor == BallColor.GREEN) {
return 0;
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
return 1;
} else {
return 2;
}
//break;
case PPG:
if (ballPositions[0].ballColor == BallColor.GREEN) {
return 1;
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
return 0;
} else {
return 2;
}
//break;
case NONE:
return 0;
//break;
}
return 0;
}
void prepareToShootMotif () {
commandedIntakePosition = bestFitMotif();
}
public void prepareShootAll(){
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_PREP;
}
public void shootAll () {
ballPositions[0].isEmpty = false;
ballPositions[1].isEmpty = false;
ballPositions[2].isEmpty = false;
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
}
public boolean shootAllComplete ()
{
return ((currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_PREP) &&
(currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_READY) &&
(currentIntakeState != Spindexer.IntakeState.SHOOTMOVING) &&
(currentIntakeState != Spindexer.IntakeState.SHOOTNEXT) &&
(currentIntakeState != Spindexer.IntakeState.SHOOTWAIT));
}
void shootAllToIntake () {
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
}
public void update() public void update()
{ {
} }
public BallColor GetFrontDriverColor () {
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()]].ballColor;
}
public BallColor GetFrontPassengerColor () {
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()]].ballColor;
}
public BallColor GetRearCenterColor () {
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
}
} }

View File

@@ -0,0 +1,219 @@
package org.firstinspires.ftc.teamcode.utils;
import android.provider.Settings;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;
public class Targeting {
MultipleTelemetry TELE;
double cancelOffsetX = 0.0; // was -40.0
double cancelOffsetY = 0.0; // was 7.0
double unitConversionFactor = 0.95;
int tileSize = 24; //inches
public final int TILE_UPPER_QUARTILE = 18;
public final int TILE_LOWER_QUARTILE = 6;
public double robotInchesX, robotInchesY = 0.0;
public int robotGridX, robotGridY = 0;
public static class Settings {
public double flywheelRPM = 0.0;
public double hoodAngle = 0.0;
public Settings (double flywheelRPM, double hoodAngle) {
this.flywheelRPM = flywheelRPM;
this.hoodAngle = hoodAngle;
}
}
// Known settings discovered using shooter test.
// Keep the fidelity at 1 floor tile for now but we could also half it if more
// accuracy is needed.
public static final Settings[][] KNOWNTARGETING;
static {
KNOWNTARGETING = new Settings[6][6];
// ROW 0 - Closet to the goals
KNOWNTARGETING[0][0] = new Settings (2300.0, 0.93);
KNOWNTARGETING[0][1] = new Settings (2300.0, 0.93);
KNOWNTARGETING[0][2] = new Settings (2500.0, 0.78);
KNOWNTARGETING[0][3] = new Settings (2800.0, 0.68);
KNOWNTARGETING[0][4] = new Settings (3000.0, 0.58);
KNOWNTARGETING[0][5] = new Settings (3000.0, 0.58);
// ROW 1
KNOWNTARGETING[1][0] = new Settings (2300.0, 0.93);
KNOWNTARGETING[1][1] = new Settings (2300.0, 0.93);
KNOWNTARGETING[1][2] = new Settings (2600.0, 0.78);
KNOWNTARGETING[1][3] = new Settings (2800.0, 0.62);
KNOWNTARGETING[1][4] = new Settings (3000.0, 0.55);
KNOWNTARGETING[1][5] = new Settings (3200.0, 0.50);
// ROW 2
KNOWNTARGETING[2][0] = new Settings (2500.0, 0.78);
KNOWNTARGETING[2][1] = new Settings (2500.0, 0.78);
KNOWNTARGETING[2][2] = new Settings (2700.0, 0.60);
KNOWNTARGETING[2][3] = new Settings (2900.0, 0.53);
KNOWNTARGETING[2][4] = new Settings (3100.0, 0.50);
KNOWNTARGETING[2][5] = new Settings (3100.0, 0.50);
// ROW 3
KNOWNTARGETING[3][0] = new Settings (2900.0, 0.50);
KNOWNTARGETING[3][1] = new Settings (2900.0, 0.50);
KNOWNTARGETING[3][2] = new Settings (2900.0, 0.50);
KNOWNTARGETING[3][3] = new Settings (3100.0, 0.47);
KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47);
KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47);
// ROW 4
KNOWNTARGETING[4][0] = new Settings (3100, 0.49);
KNOWNTARGETING[4][1] = new Settings (3100, 0.49);
KNOWNTARGETING[4][2] = new Settings (3100, 0.5);
KNOWNTARGETING[4][3] = new Settings (3200, 0.5);
KNOWNTARGETING[4][4] = new Settings (3250, 0.49);
KNOWNTARGETING[4][5] = new Settings (3300, 0.49);
// ROW 5
KNOWNTARGETING[5][0] = new Settings (3200, 0.48);
KNOWNTARGETING[5][1] = new Settings (3200, 0.48);
KNOWNTARGETING[5][2] = new Settings (3300, 0.48);
KNOWNTARGETING[5][3] = new Settings (3350, 0.48);
KNOWNTARGETING[5][4] = new Settings (3350, 0.48);
KNOWNTARGETING[5][5] = new Settings (3350, 0.48);
}
public Targeting()
{
}
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
Settings recommendedSettings = new Settings(0.0, 0.0);
double cos45 = Math.cos(Math.toRadians(-45));
double sin45 = Math.sin(Math.toRadians(-45));
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
// Convert robot coordinates to inches
robotInchesX = rotatedX * unitConversionFactor;
robotInchesY = rotatedY * unitConversionFactor;
// Find approximate location in the grid
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
int remX = Math.floorMod((int)robotInchesX, tileSize);
int remY = Math.floorMod((int)robotInchesX, tileSize);
// Determine if we need to interpolate based on tile position.
// if near upper or lower quarter or tile interpolate with next tile.
int x0 = 0;
int y0 = 0;
int x1 = 0;
int y1 = 0;
interpolate = false;
if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
(robotGridX < 5) && (robotGridY <5)) {
// +X, +Y
interpolate = true;
x0 = robotGridX;
x1 = robotGridX + 1;
y0 = robotGridY;
y1 = robotGridY + 1;
} else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
(robotGridX > 0) && (robotGridY > 0)) {
// -X, -Y
interpolate = true;
x0 = robotGridX - 1;
x1 = robotGridX;
y0 = robotGridY - 1;
y1 = robotGridY;
} else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
(robotGridX < 5) && (robotGridY > 0)) {
// +X, -Y
interpolate = true;
x0 = robotGridX;
x1 = robotGridX + 1;
y0 = robotGridY - 1;
y1 = robotGridY;
} else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
(robotGridX > 0) && (robotGridY < 5)) {
// -X, +Y
interpolate = true;
x0 = robotGridX - 1;
x1 = robotGridX;
y0 = robotGridY;
y1 = robotGridY + 1;
} else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) {
// -X, Y
interpolate = true;
x0 = robotGridX - 1;
x1 = robotGridX;
y0 = robotGridY;
y1 = robotGridY;
} else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) {
// X, -Y
interpolate = true;
x0 = robotGridX;
x1 = robotGridX;
y0 = robotGridY - 1;
y1 = robotGridY;
} else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) {
// +X, Y
interpolate = true;
x0 = robotGridX;
x1 = robotGridX + 1;
y0 = robotGridY;
y1 = robotGridY;
} else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) {
// X, +Y
interpolate = true;
x0 = robotGridX;
x1 = robotGridX;
y0 = robotGridY;
y1 = robotGridY + 1;
} else {
interpolate = false;
}
//clamp
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
// basic search
if(true) { //!interpolate) {
if ((robotGridY < 6) && (robotGridX <6)) {
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
}
return recommendedSettings;
} else {
// bilinear interpolation
//int x0 = robotGridX;
//int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
//int y0 = robotGridY;
//int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
// double x = (robotInchesX - (x0 * tileSize)) / tileSize;
// double y = (robotInchesY - (y0 * tileSize)) / tileSize;
// double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM;
// double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM;
// double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM;
// double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM;
//
// double angle00 = KNOWNTARGETING[y0][x0].hoodAngle;
// double angle10 = KNOWNTARGETING[y0][x1].hoodAngle;
// double angle01 = KNOWNTARGETING[y1][x0].hoodAngle;
// double angle11 = KNOWNTARGETING[y1][x1].hoodAngle;
// recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11;
// recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11;
// Average target tiles
recommendedSettings.flywheelRPM = (KNOWNTARGETING[x0][y0].flywheelRPM + KNOWNTARGETING[x1][y1].flywheelRPM)/2.0;
recommendedSettings.hoodAngle = (KNOWNTARGETING[x0][y0].hoodAngle + KNOWNTARGETING[x1][y1].hoodAngle)/2.0;
return recommendedSettings;
}
}
}

View File

@@ -0,0 +1,302 @@
package org.firstinspires.ftc.teamcode.utils;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static java.lang.Math.abs;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.roadrunner.Pose2d;
import com.arcrobotics.ftclib.controller.PIDController;
import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
import java.util.List;
@Config
public class Turret {
public static double turretTolerance = 0.02;
public static double turrPosScalar = 0.00011264432;
public static double turret180Range = 0.4;
public static double turrDefault = 0.4;
public static double turrMin = 0.15;
public static double turrMax = 0.85;
public static double visionCorrectionGain = 0.08; // Single tunable gain
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
public static double cameraBearingEqual = 0.5; // Deadband
// TODO: tune these values for limelight
public static double clampTolerance = 0.03;
Robot robot;
MultipleTelemetry TELE;
Limelight3A webcam;
double tx = 0.0;
double ty = 0.0;
double limelightPosX = 0.0;
double limelightPosY = 0.0;
private boolean lockOffset = false;
private int obeliskID = 0;
private double offset = 0.0;
private double currentTrackOffset = 0.0;
private int currentTrackCount = 0;
private double permanentOffset = 0.0;
LLResult result;
private PIDController bearingPID;
public static double B_PID_P = 0.3, B_PID_I = 0.0, B_PID_D = 0.05;
boolean bearingAligned = false;
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
this.TELE = tele;
this.robot = rob;
this.webcam = cam;
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
}
public void zeroTurretEncoder() {
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
}
public double getTurrPos() {
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
}
public void manualSetTurret(double pos) {
robot.turr1.setPosition(pos);
robot.turr2.setPosition(1 - pos);
}
public boolean turretEqual(double pos) {
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
}
private void limelightRead() { // only for tracking purposes, not general reads
if (redAlliance) {
webcam.pipelineSwitch(4);
} else {
webcam.pipelineSwitch(2);
}
result = webcam.getLatestResult();
if (result != null) {
if (result.isValid()) {
tx = result.getTx();
ty = result.getTy();
// MegaTag1 code for receiving position
Pose3D botpose = result.getBotpose();
if (botpose != null) {
limelightPosX = botpose.getPosition().x;
limelightPosY = botpose.getPosition().y;
}
}
}
}
public double getBearing() {
tx = 1000;
limelightRead();
return tx;
}
public double getTy() {
return ty;
}
public double getLimelightX() {
return limelightPosX;
}
public double getLimelightY() {
return limelightPosY;
}
public int detectObelisk() {
webcam.pipelineSwitch(1);
LLResult result = webcam.getLatestResult();
if (result != null && result.isValid()) {
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
for (LLResultTypes.FiducialResult fiducial : fiducials) {
obeliskID = fiducial.getFiducialId();
}
}
return obeliskID;
}
public int getObeliskID() {
return obeliskID;
}
public void zeroOffset() {
offset = 0.0;
}
public void lockOffset(boolean lock) {
lockOffset = lock;
}
/*
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
*/
private double bearingAlign (LLResult llResult) {
double bearingOffset = 0.0;
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
final double MIN_OFFSET_POWER = 0.15;
final double TARGET_POSITION_TOLERANCE = 1.0;
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
final double DRIVE_POWER_REDUCTION = 2.0;
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
bearingAligned = true;
} else {
bearingAligned = false;
}
// Only with valid data and if too far off target
if (llResult.isValid() && !bearingAligned)
{
// Adjust Robot Speed based on how far the target is located
// Only drive at half speed max
// switched to PID but original formula left for reference in comments
//drivePower = targetTx/HORIZONTAL_FOV_RANGE / DRIVE_POWER_REDUCTION;
bearingOffset = -(bearingPID.calculate(targetTx, 0.0));
// // Make sure we have enough power to actually drive the wheels
// if (abs(bearingOffset) < MIN_OFFSET_POWER) {
// if (bearingOffset > 0.0) {
// bearingOffset = MIN_OFFSET_POWER;
// } else {
// bearingOffset = -MIN_OFFSET_POWER;
// }
//
// }
}
return bearingOffset;
}
public void trackGoal(Pose2d deltaPos) {
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
// Angle from robot to goal in robot frame
double desiredTurretAngleDeg = Math.toDegrees(
Math.atan2(deltaPos.position.y, deltaPos.position.x)
);
// Robot heading (field → robot)
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
// Turret angle needed relative to robot
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
turretAngleDeg = -turretAngleDeg;
// Normalize to [-180, 180]
while (turretAngleDeg > 180) turretAngleDeg -= 360;
while (turretAngleDeg < -180) turretAngleDeg += 360;
/* ---------------- LIMELIGHT VISION CORRECTION ---------------- */
// Update local limelight results
//double tagBearingDeg = getBearing(); // + = target is to the left
//boolean hasValidTarget = (tagBearingDeg != 1000.0);
turretAngleDeg += permanentOffset;
limelightRead();
// Active correction if we see the target
if (result.isValid() && !lockOffset) {
currentTrackOffset += bearingAlign(result);
currentTrackCount++;
// double bearingError = Math.abs(tagBearingDeg);
//
// if (bearingError > cameraBearingEqual) {
// // Apply sqrt scaling to reduce aggressive corrections at large errors
// double filteredBearing = Math.signum(tagBearingDeg) * Math.sqrt(Math.abs(tagBearingDeg));
//
// // Calculate correction
// double offsetChange = visionCorrectionGain * filteredBearing;
//
// // Limit rate of change to prevent jumps
// offsetChange = Math.max(-maxOffsetChangePerCycle,
// Math.min(maxOffsetChangePerCycle, offsetChange));
//
// // Accumulate the correction
// offset += offsetChange;
//
// TELE.addData("Bearing Error", tagBearingDeg);
// TELE.addData("Offset Change", offsetChange);
// TELE.addData("Total Offset", offset);
// } else {
// // When centered, lock in the learned offset
// permanentOffset = offset;
// offset = 0.0;
// }
} else {
// only store perma update after 20+ successful tracks
// this did not work good in testing; only current works best so far.
// if (currentTrackCount > 20) {
// offset = currentTrackOffset;
// }
currentTrackOffset = 0.0;
currentTrackCount = 0;
}
// Apply accumulated offset
turretAngleDeg += offset + currentTrackOffset;
/* ---------------- ANGLE → SERVO POSITION ---------------- */
double targetTurretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
// Clamp to physical servo limits
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
// Interpolate towards target position
double currentPos = getTurrPos();
double turretPos = targetTurretPos;
if (targetTurretPos == turrMin) {
turretPos = turrMin;
} else if (targetTurretPos == turrMax) {
turretPos = turrMax;
}
// Set servo positions
robot.turr1.setPosition(turretPos);
robot.turr2.setPosition(1.0 - turretPos);
/* ---------------- TELEMETRY ---------------- */
TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
TELE.addData("Target Pos", "%.3f", targetTurretPos);
TELE.addData("Current Pos", "%.3f", currentPos);
TELE.addData("Commanded Pos", "%.3f", turretPos);
TELE.addData("LL Valid", result.isValid());
TELE.addData("LL getTx", result.getTx());
TELE.addData("LL Offset", offset);
//TELE.addData("Bearing Error", hasValidTarget ? String.format("%.2f", tagBearingDeg) : "NO TARGET");
TELE.addData("Learned Offset", "%.2f", offset);
}
}

View File

@@ -29,7 +29,7 @@ dependencies {
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash implementation "com.acmerobotics.dashboard:dashboard:0.5.1" //FTC Dash
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB

View File

@@ -25,5 +25,9 @@ allprojects {
} }
repositories { repositories {
repositories {
mavenCentral() mavenCentral()
google()
maven { url 'https://maven.pedropathing.com' }
}
} }