Compare commits
3 Commits
93ed2208a9
...
organize/e
| Author | SHA1 | Date | |
|---|---|---|---|
| 5931b2e7fa | |||
| 73f804bd2f | |||
| 0a81eb60d3 |
@@ -1,8 +1,8 @@
|
|||||||
<?xml version="1.0" encoding="utf-8"?>
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
|
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
|
||||||
xmlns:tools="http://schemas.android.com/tools"
|
xmlns:tools="http://schemas.android.com/tools"
|
||||||
android:versionCode="61"
|
android:versionCode="60"
|
||||||
android:versionName="11.1">
|
android:versionName="11.0">
|
||||||
|
|
||||||
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
|
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
|
||||||
|
|
||||||
|
|||||||
@@ -92,22 +92,24 @@ public class ConceptAprilTag extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
if (opModeIsActive()) {
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -88,22 +88,24 @@ public class ConceptAprilTagEasy extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
if (opModeIsActive()) {
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -81,25 +81,27 @@ public class ConceptAprilTagSwitchableCameras extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
if (opModeIsActive()) {
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
telemetryCameraSwitching();
|
telemetryCameraSwitching();
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
|
}
|
||||||
|
|
||||||
|
doCameraSwitching();
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
doCameraSwitching();
|
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -83,22 +83,6 @@ public class ConceptGamepadEdgeDetection extends LinearOpMode {
|
|||||||
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
|
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
|
||||||
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
|
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
|
||||||
|
|
||||||
// Add an empty line to separate the buttons in telemetry
|
|
||||||
telemetry.addLine();
|
|
||||||
|
|
||||||
// Add the status of the Gamepad 1 Left trigger
|
|
||||||
telemetry.addData("Gamepad 1 Left Trigger Pressed", gamepad1.leftTriggerWasPressed());
|
|
||||||
telemetry.addData("Gamepad 1 Left Trigger Released", gamepad1.leftTriggerWasReleased());
|
|
||||||
telemetry.addData("Gamepad 1 Left Trigger Status", gamepad1.left_trigger_pressed);
|
|
||||||
|
|
||||||
// Add an empty line to separate the buttons in telemetry
|
|
||||||
telemetry.addLine();
|
|
||||||
|
|
||||||
// Add the status of the Gamepad 1 Right trigger
|
|
||||||
telemetry.addData("Gamepad 1 Right Trigger Pressed", gamepad1.rightTriggerWasPressed());
|
|
||||||
telemetry.addData("Gamepad 1 Right Trigger Released", gamepad1.rightTriggerWasReleased());
|
|
||||||
telemetry.addData("Gamepad 1 Right Trigger Status", gamepad1.right_trigger_pressed);
|
|
||||||
|
|
||||||
// Add a note that the telemetry is only updated every 2 seconds
|
// Add a note that the telemetry is only updated every 2 seconds
|
||||||
telemetry.addLine("\nTelemetry is updated every 2 seconds.");
|
telemetry.addLine("\nTelemetry is updated every 2 seconds.");
|
||||||
|
|
||||||
|
|||||||
@@ -27,7 +27,7 @@
|
|||||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
|
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|||||||
@@ -27,7 +27,7 @@
|
|||||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
|
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|||||||
15
README.md
15
README.md
@@ -59,21 +59,6 @@ The readme.md file located in the [/TeamCode/src/main/java/org/firstinspires/ftc
|
|||||||
|
|
||||||
# Release Information
|
# Release Information
|
||||||
|
|
||||||
## Version 11.1 (20251231-104637)
|
|
||||||
|
|
||||||
### Enhancements
|
|
||||||
|
|
||||||
* Gamepad triggers can now be accessed as booleans and have edge detection supported.
|
|
||||||
* GoBildaPinpointDriver now supports Pinpoint v2 functionality
|
|
||||||
* Adds webcam calibrations for goBILDA's USB camera.
|
|
||||||
|
|
||||||
### Bug Fixes
|
|
||||||
* Fixes issue [1654](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1654) in GoBildaPinpointDriver that caused error if resolution was set in other than MM
|
|
||||||
* Fixes issue [1628](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1628) Blocks editor displays incorrect Java code for gamepad edge detection blocks.
|
|
||||||
* Fixes possible race condition issue [1884](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1884) on Driver Station startup when Driver Station name doesn't match the Robot Controller name.
|
|
||||||
* Fixes issue [1863](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1863) - Incorrect package paths in samples.
|
|
||||||
* Fixes an issue where an OnBotJava filename that begins with a lowercase character would fail to properly rename the file if the user tried to rename it so that it begins with an uppercase character.
|
|
||||||
|
|
||||||
## Version 11.0 (20250827-105138)
|
## Version 11.0 (20250827-105138)
|
||||||
|
|
||||||
### Enhancements
|
### Enhancements
|
||||||
|
|||||||
@@ -12,25 +12,8 @@
|
|||||||
// Custom definitions may go here
|
// Custom definitions may go here
|
||||||
|
|
||||||
// Include common definitions from above.
|
// Include common definitions from above.
|
||||||
|
|
||||||
buildscript {
|
|
||||||
repositories {
|
|
||||||
mavenCentral()
|
|
||||||
maven {
|
|
||||||
url "https://repo.dairy.foundation/releases"
|
|
||||||
}
|
|
||||||
}
|
|
||||||
dependencies {
|
|
||||||
classpath "dev.frozenmilk:Load:0.2.4"
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
apply from: '../build.common.gradle'
|
apply from: '../build.common.gradle'
|
||||||
apply from: '../build.dependencies.gradle'
|
apply from: '../build.dependencies.gradle'
|
||||||
// there should be 2 or 3 more lines that start with 'apply plugin:' here
|
|
||||||
apply plugin: 'dev.frozenmilk.sinister.sloth.load'
|
|
||||||
|
|
||||||
|
|
||||||
android {
|
android {
|
||||||
namespace = 'org.firstinspires.ftc.teamcode'
|
namespace = 'org.firstinspires.ftc.teamcode'
|
||||||
@@ -45,32 +28,14 @@ repositories {
|
|||||||
maven {
|
maven {
|
||||||
url = 'https://maven.brott.dev/'
|
url = 'https://maven.brott.dev/'
|
||||||
}
|
}
|
||||||
// Dairy releases repository
|
|
||||||
maven {
|
|
||||||
url = "https://repo.dairy.foundation/releases"
|
|
||||||
}
|
|
||||||
// Dairy snapshots repository
|
|
||||||
maven {
|
|
||||||
url = "https://repo.dairy.foundation/snapshots"
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation project(':FtcRobotController')
|
implementation project(':FtcRobotController')
|
||||||
implementation("dev.frozenmilk.sinister:Sloth:0.2.4")
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
||||||
|
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
||||||
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
||||||
|
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // core
|
implementation 'org.ftclib.ftclib:core:2.1.1' // core
|
||||||
implementation("com.acmerobotics.roadrunner:ftc:0.1.25") {
|
|
||||||
exclude group: "com.acmerobotics.dashboard"
|
|
||||||
}
|
|
||||||
implementation("com.acmerobotics.roadrunner:actions:1.0.1") {
|
|
||||||
exclude group: "com.acmerobotics.dashboard"
|
|
||||||
}
|
|
||||||
implementation("com.acmerobotics.roadrunner:core:1.0.1") {
|
|
||||||
exclude group: "com.acmerobotics.dashboard"
|
|
||||||
}
|
|
||||||
|
|
||||||
implementation("com.acmerobotics.slothboard:dashboard:0.2.4+0.5.1") //Slothdashboard
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,606 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoClose_V3 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
LimelightManager limelightManager;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
public static double holdTurrPow = 0.1;
|
||||||
|
|
||||||
|
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b1 = 0, b2 = 0, b3 = 0;
|
||||||
|
boolean gpp = false, pgp = false, ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !flywheel.getSteady();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
limelightManager.update();
|
||||||
|
int id = limelightManager.detectFiducial();
|
||||||
|
|
||||||
|
if (id == 21) gpp = true;
|
||||||
|
else if (id == 22) pgp = true;
|
||||||
|
else if (id == 23) ppg = true;
|
||||||
|
|
||||||
|
TELE.addData("Fiducial ID", id);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
LimelightManager.LimelightMode mode = redAlliance ?
|
||||||
|
LimelightManager.LimelightMode.RED_GOAL :
|
||||||
|
LimelightManager.LimelightMode.BLUE_GOAL;
|
||||||
|
limelightManager.switchMode(mode);
|
||||||
|
|
||||||
|
double turretTarget = redAlliance ? turret_redClose : turret_blueClose;
|
||||||
|
double turretPID = servo.setTurrPos(turretTarget);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turretTarget);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex(double spindexer, int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double spinPID = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (servo.spinEqual(spindexer)){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
robot.turr1.setPower(holdTurrPow);
|
||||||
|
robot.turr2.setPower(holdTurrPow);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = spindexer_intakePos1;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double pow = 1.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
robot.intake.setPower(pow);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (!servo.spinEqual(position)){
|
||||||
|
double spinPID = servo.setSpinPos(position);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
|
if (s2D > 60){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
} else if (s3D > 33){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
flywheel = new FlywheelV2();
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
||||||
|
limelightManager.init();
|
||||||
|
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()){
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
}
|
||||||
|
|
||||||
|
double turrPID;
|
||||||
|
|
||||||
|
if (redAlliance){
|
||||||
|
turrPID = servo.setTurrPos(turret_detectRedClose);
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
} else {
|
||||||
|
turrPID = servo.setTurrPos(turret_detectBlueClose);
|
||||||
|
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPower(turrPID);
|
||||||
|
robot.turr2.setPower(-turrPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
ColorDetect(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
limelightManager.update();
|
||||||
|
bearing = limelightManager.getBearing();
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
|
||||||
|
// Define sequences based on obelisk configuration
|
||||||
|
double[][] sequences = {
|
||||||
|
{1, 2, 3}, {1, 3, 2}, {2, 1, 3}, {2, 3, 1}, {3, 1, 2}, {3, 2, 1}
|
||||||
|
};
|
||||||
|
|
||||||
|
double[] sequence = null;
|
||||||
|
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[0]; // 1,2,3
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[2]; // 2,1,3
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[4]; // 3,1,2
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[0];
|
||||||
|
else if (b2 == 2) sequence = sequences[2];
|
||||||
|
else if (b3 == 2) sequence = sequences[4];
|
||||||
|
} else sequence = sequences[0];
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[2]; // 2,1,3
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[0]; // 1,2,3
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[3]; // 2,3,1
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[2];
|
||||||
|
else if (b2 == 2) sequence = sequences[0];
|
||||||
|
else if (b3 == 2) sequence = sequences[3];
|
||||||
|
} else sequence = sequences[2];
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 == b3) sequence = sequences[4]; // 3,1,2
|
||||||
|
else if (b2 == 2 && b1 == b3) sequence = sequences[5]; // 3,2,1
|
||||||
|
else if (b3 == 2 && b1 == b2) sequence = sequences[0]; // 1,2,3
|
||||||
|
else sequence = sequences[0];
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) sequence = sequences[4];
|
||||||
|
else if (b2 == 2) sequence = sequences[5];
|
||||||
|
else if (b3 == 2) sequence = sequences[0];
|
||||||
|
} else sequence = sequences[4];
|
||||||
|
} else sequence = sequences[0];
|
||||||
|
|
||||||
|
executeShootingSequence(sequence);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
private void executeShootingSequence(double[] sequence) {
|
||||||
|
double[] ballPositions = {
|
||||||
|
spindexer_outtakeBall1,
|
||||||
|
spindexer_outtakeBall2,
|
||||||
|
spindexer_outtakeBall3
|
||||||
|
};
|
||||||
|
|
||||||
|
for (double ball : sequence) {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(ballPositions[(int) ball - 1], AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,619 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.LimelightManager;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
|
public class AutoFar_V1 extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
FlywheelV2 flywheel;
|
||||||
|
Servos servo;
|
||||||
|
LimelightManager limelightManager;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.7;
|
||||||
|
public static double intake2Time = 3.0;
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
public static double holdTurrPow = 0.1;
|
||||||
|
|
||||||
|
// Ball color detection: 0 = no ball, 1 = green, 2 = purple
|
||||||
|
int b1 = 0, b2 = 0, b3 = 0;
|
||||||
|
boolean gpp = false, pgp = false, ppg = false;
|
||||||
|
double powPID = 0.0;
|
||||||
|
double bearing = 0.0;
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !flywheel.getSteady();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
limelightManager.update();
|
||||||
|
int id = limelightManager.detectFiducial();
|
||||||
|
|
||||||
|
if (id == 21) gpp = true;
|
||||||
|
else if (id == 22) pgp = true;
|
||||||
|
else if (id == 23) ppg = true;
|
||||||
|
|
||||||
|
TELE.addData("Fiducial ID", id);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg) {
|
||||||
|
LimelightManager.LimelightMode mode = redAlliance ?
|
||||||
|
LimelightManager.LimelightMode.RED_GOAL :
|
||||||
|
LimelightManager.LimelightMode.BLUE_GOAL;
|
||||||
|
limelightManager.switchMode(mode);
|
||||||
|
|
||||||
|
double turretTarget = redAlliance ? turret_redFar : turret_blueFar;
|
||||||
|
double turretPID = servo.setTurrPos(turretTarget);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turretTarget);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex(double spindexer, int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double spinPID = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (servo.spinEqual(spindexer)){
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
robot.turr1.setPower(holdTurrPow);
|
||||||
|
robot.turr2.setPower(holdTurrPow);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = spindexer_intakePos1;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double pow = 1.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
robot.intake.setPower(pow);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (!servo.spinEqual(position)){
|
||||||
|
double spinPID = servo.setSpinPos(position);
|
||||||
|
robot.spin1.setPower(spinPID);
|
||||||
|
robot.spin2.setPower(-spinPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){
|
||||||
|
if (s2D > 60){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
}
|
||||||
|
} else if (s3D > 33){
|
||||||
|
if (servo.spinEqual(spindexer_intakePos1)){
|
||||||
|
position = spindexer_intakePos3;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos2)){
|
||||||
|
position = spindexer_intakePos1;
|
||||||
|
} else if (servo.spinEqual(spindexer_intakePos3)){
|
||||||
|
position = spindexer_intakePos2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
if (getRuntime() - stamp - intakeTime < 1){
|
||||||
|
pow = -2*(getRuntime() - stamp - intakeTime);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 43) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 60) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 33) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
flywheel = new FlywheelV2();
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
limelightManager = new LimelightManager(hardwareMap, Robot.usingLimelight);
|
||||||
|
limelightManager.init();
|
||||||
|
limelightManager.switchMode(LimelightManager.LimelightMode.OBELISK_DETECTION);
|
||||||
|
|
||||||
|
//TODO: add positions to develop auto
|
||||||
|
|
||||||
|
TrajectoryActionBuilder park = drive.actionBuilder(new Pose2d(0,0,0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rfx1, rfy1), rfh1);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto -= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.crossWasPressed()){
|
||||||
|
redAlliance = !redAlliance;
|
||||||
|
}
|
||||||
|
|
||||||
|
double turrPID;
|
||||||
|
|
||||||
|
if (redAlliance){
|
||||||
|
turrPID = servo.setTurrPos(turret_detectRedClose);
|
||||||
|
} else {
|
||||||
|
turrPID = servo.setTurrPos(turret_detectBlueClose);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.turr1.setPower(turrPID);
|
||||||
|
robot.turr2.setPower(-turrPID);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAutoFar);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.addData("Spin Pos", servo.getSpinPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
initShooter(AUTO_FAR_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(park.build());
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
//TODO: adjust this according to Teleop numbers
|
||||||
|
public void detectTag() {
|
||||||
|
limelightManager.update();
|
||||||
|
bearing = limelightManager.getBearing();
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_FAR_VEL),
|
||||||
|
Shoot(AUTO_FAR_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -1,938 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
|
||||||
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.spindexer_outtakeBall2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
|
||||||
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.utils.Targeting.turretInterpolate;
|
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
|
|
||||||
|
|
||||||
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.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;
|
|
||||||
|
|
||||||
import java.util.Objects;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class Auto_LT_Far extends LinearOpMode {
|
|
||||||
public static double shoot0Vel = 3300, shoot0Hood = 0.48 + hoodOffset;
|
|
||||||
public static double autoSpinStartPos = 0.2;
|
|
||||||
public static double shoot0SpinSpeedIncrease = 0.015;
|
|
||||||
public static double shoot0XTolerance = 1.0;
|
|
||||||
public static double redTurretShootPos = 0.05;
|
|
||||||
public static double blueTurretShootPos = -0.05;
|
|
||||||
public static int fwdTime = 200, strafeTime = 2300;
|
|
||||||
double xLeave, yLeave, hLeave;
|
|
||||||
public static int sleepTime = 1300;
|
|
||||||
public int motif = 0;
|
|
||||||
double turretShootPos = 0.0;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Servos servos;
|
|
||||||
Spindexer spindexer;
|
|
||||||
Flywheel flywheel;
|
|
||||||
Turret turret;
|
|
||||||
Targeting targeting;
|
|
||||||
Targeting.Settings targetingSettings;
|
|
||||||
double firstSpindexShootPos = autoSpinStartPos;
|
|
||||||
boolean shootForward = true;
|
|
||||||
double xShoot, yShoot, hShoot;
|
|
||||||
private int driverSlotGreen = 0;
|
|
||||||
private int passengerSlotGreen = 0;
|
|
||||||
int rearSlotGreen = 0;
|
|
||||||
int mostGreenSlot = 0;
|
|
||||||
double pickupGateX = 0, pickupGateY = 0, pickupGateH = 0;
|
|
||||||
double pickupZoneX = 0, pickupZoneY = 0, pickupZoneH = 0;
|
|
||||||
public static double firstShootTime = 0.3;
|
|
||||||
public static double flywheel0Time = 3.5;
|
|
||||||
public static double shoot0Time = 2;
|
|
||||||
boolean gatePickup = false;
|
|
||||||
boolean stack3 = true;
|
|
||||||
double xStackPickupA, yStackPickupA, hStackPickupA;
|
|
||||||
double xStackPickupB, yStackPickupB, hStackPickupB;
|
|
||||||
public static int pickupStackSpeed = 15;
|
|
||||||
int prevMotif = 0;
|
|
||||||
|
|
||||||
public Action prepareShootAll(double colorSenseTime, double time, int motif_id) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
double spindexerWiggle = 0.01;
|
|
||||||
|
|
||||||
boolean decideGreenSlot = false;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.addData("motif", motif_id);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
|
||||||
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
|
|
||||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
|
||||||
|
|
||||||
spindexer.detectBalls(true, true);
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
driverSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
passengerSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
rearSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
spindexer.setIntakePower(1);
|
|
||||||
|
|
||||||
decideGreenSlot = true;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else if (decideGreenSlot) {
|
|
||||||
|
|
||||||
if (driverSlotGreen >= passengerSlotGreen && driverSlotGreen >= rearSlotGreen) {
|
|
||||||
mostGreenSlot = 3;
|
|
||||||
} else if (passengerSlotGreen >= driverSlotGreen && passengerSlotGreen >= rearSlotGreen) {
|
|
||||||
mostGreenSlot = 2;
|
|
||||||
} else {
|
|
||||||
mostGreenSlot = 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
decideGreenSlot = false;
|
|
||||||
|
|
||||||
if (motif_id == 21) {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
|
||||||
shootForward = true;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = false;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
}
|
|
||||||
} else if (motif_id == 22) {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = false;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
|
||||||
shootForward = true;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
|
||||||
shootForward = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
|
||||||
// TELE.addData("MostGreenSlot", mostGreenSlot);
|
|
||||||
// TELE.update();
|
|
||||||
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
|
||||||
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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();
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
spindexer.setIntakePower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.setIntakePower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
if ((getRuntime() - stamp < shootTime && servos.getSpinPos() < spinEndPos) || shooterTicker == 0) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(autoSpinStartPos)) {
|
|
||||||
servos.setSpinPos(autoSpinStartPos);
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = servos.getSpinCmdPos();
|
|
||||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
|
|
||||||
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();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
spindexer.setIntakePower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.setIntakePower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < shootTime) {
|
|
||||||
|
|
||||||
if (getRuntime() - stamp < firstShootTime) {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = servos.getSpinCmdPos();
|
|
||||||
|
|
||||||
if (shootForward) {
|
|
||||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
|
||||||
} else {
|
|
||||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
|
|
||||||
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();
|
|
||||||
spindexer.setIntakePower(1);
|
|
||||||
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Full?", spindexer.isFull());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return ((System.currentTimeMillis() - stamp) < (intakeTime * 1000)) && !spindexer.isFull();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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();
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
turret.setTurret(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();
|
|
||||||
|
|
||||||
if (shouldFinish){
|
|
||||||
if (redAlliance){
|
|
||||||
robot.limelight.pipelineSwitch(4);
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(2);
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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++;
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
servos.setHoodPos(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);
|
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
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);
|
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
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;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
// initialize path variables here
|
|
||||||
TrajectoryActionBuilder leave3Ball = null;
|
|
||||||
TrajectoryActionBuilder leaveFromShoot = null;
|
|
||||||
TrajectoryActionBuilder pickup3 = null;
|
|
||||||
TrajectoryActionBuilder shoot3 = null;
|
|
||||||
|
|
||||||
@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.start();
|
|
||||||
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
|
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
|
|
||||||
turret.setTurret(turrDefault);
|
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, autoStart);
|
|
||||||
|
|
||||||
servos.setSpinPos(autoSpinStartPos);
|
|
||||||
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
// Recalibration in initialization
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
if (gamepad2.triangle) {
|
|
||||||
autoStart = drive.localizer.getPose(); // use this position as starting position
|
|
||||||
gamepad2.rumble(1000);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.squareWasPressed()){
|
|
||||||
robot.limelight.start();
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
gamepad2.rumble(500);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.leftBumperWasPressed()){
|
|
||||||
gatePickup = !gatePickup;
|
|
||||||
}
|
|
||||||
if (gamepad2.rightBumperWasPressed()){
|
|
||||||
stack3 = !stack3;
|
|
||||||
}
|
|
||||||
|
|
||||||
turret.setTurret(turretShootPos);
|
|
||||||
|
|
||||||
robot.hood.setPosition(shoot0Hood);
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadLeftWasPressed()) {
|
|
||||||
turrDefault -= 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadRightWasPressed()) {
|
|
||||||
turrDefault += 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
robot.light.setPosition(0.28);
|
|
||||||
|
|
||||||
xLeave = rLeaveX;
|
|
||||||
yLeave = rLeaveY;
|
|
||||||
hLeave = rLeaveH;
|
|
||||||
|
|
||||||
xShoot = rShootX;
|
|
||||||
yShoot = rShootY;
|
|
||||||
hShoot = rShootH;
|
|
||||||
|
|
||||||
xStackPickupA = rStackPickupAX;
|
|
||||||
yStackPickupA = rStackPickupAY;
|
|
||||||
hStackPickupA = rStackPickupAH;
|
|
||||||
|
|
||||||
xStackPickupB = rStackPickupBX;
|
|
||||||
yStackPickupB = rStackPickupBY;
|
|
||||||
hStackPickupB = rStackPickupBH;
|
|
||||||
|
|
||||||
turretShootPos = turrDefault + redTurretShootPos;
|
|
||||||
} else {
|
|
||||||
robot.light.setPosition(0.6);
|
|
||||||
|
|
||||||
xLeave = bLeaveX;
|
|
||||||
yLeave = bLeaveY;
|
|
||||||
hLeave = bLeaveH;
|
|
||||||
|
|
||||||
xShoot = bShootX;
|
|
||||||
yShoot = bShootY;
|
|
||||||
hShoot = bShootH;
|
|
||||||
|
|
||||||
xStackPickupA = bStackPickupAX;
|
|
||||||
yStackPickupA = bStackPickupAY;
|
|
||||||
hStackPickupA = bStackPickupAH;
|
|
||||||
|
|
||||||
xStackPickupB = bStackPickupBX;
|
|
||||||
yStackPickupB = bStackPickupBY;
|
|
||||||
hStackPickupB = bStackPickupBH;
|
|
||||||
|
|
||||||
turretShootPos = turrDefault + blueTurretShootPos;
|
|
||||||
}
|
|
||||||
|
|
||||||
leave3Ball = drive.actionBuilder(autoStart)
|
|
||||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
|
||||||
|
|
||||||
leaveFromShoot = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
|
||||||
|
|
||||||
pickup3 = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xStackPickupA, yStackPickupA), Math.toRadians(hStackPickupA))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xStackPickupB, yStackPickupB), Math.toRadians(hStackPickupB),
|
|
||||||
new TranslationalVelConstraint(pickupStackSpeed));
|
|
||||||
|
|
||||||
shoot3 = drive.actionBuilder(new Pose2d(xStackPickupB, yStackPickupB, Math.toRadians(hStackPickupB)))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
|
||||||
|
|
||||||
TELE.addData("Red?", redAlliance);
|
|
||||||
TELE.addData("Turret Default", turrDefault);
|
|
||||||
TELE.addData("Gate Cycle?", gatePickup);
|
|
||||||
TELE.addData("Pickup Stack?", stack3);
|
|
||||||
TELE.addData("Start Position", autoStart);
|
|
||||||
TELE.addData("Current Position", drive.localizer.getPose()); // use this to test standstill drift
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
// Currently only shoots; keep this start and modify times and then add extra paths
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
double stamp = getRuntime();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
startAuto();
|
|
||||||
|
|
||||||
if (stack3){
|
|
||||||
//cycleStackFar();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gatePickup || stack3){
|
|
||||||
leave();
|
|
||||||
} else {
|
|
||||||
leave3Ball();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Actual way to end autonomous in to find final position
|
|
||||||
while (opModeIsActive()) {
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(0);
|
|
||||||
|
|
||||||
TELE.addLine("finished");
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void startAuto(){
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
manageFlywheel(
|
|
||||||
shoot0Vel,
|
|
||||||
shoot0Hood,
|
|
||||||
flywheel0Time,
|
|
||||||
0.501,
|
|
||||||
0.501,
|
|
||||||
shoot0XTolerance,
|
|
||||||
0.501
|
|
||||||
)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
shootAll((int) shoot0Vel, shoot0Time, shoot0SpinSpeedIncrease)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
void leave3Ball(){
|
|
||||||
assert leave3Ball != null;
|
|
||||||
Actions.runBlocking(leave3Ball.build());
|
|
||||||
}
|
|
||||||
|
|
||||||
void leave(){
|
|
||||||
assert leaveFromShoot != null;
|
|
||||||
Actions.runBlocking(leaveFromShoot.build());
|
|
||||||
}
|
|
||||||
|
|
||||||
// void cycleStackFar(){
|
|
||||||
// Actions.runBlocking(
|
|
||||||
// new ParallelAction(
|
|
||||||
// pickup3.build(),
|
|
||||||
// manageShooterAuto(
|
|
||||||
// intake3Time,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501
|
|
||||||
// ),
|
|
||||||
// intake(intake3Time),
|
|
||||||
// detectObelisk(
|
|
||||||
// intake3Time,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// obeliskTurrPos3
|
|
||||||
// )
|
|
||||||
//
|
|
||||||
// )
|
|
||||||
// );
|
|
||||||
//
|
|
||||||
// motif = turret.getObeliskID();
|
|
||||||
//
|
|
||||||
// if (motif == 0) motif = prevMotif;
|
|
||||||
// prevMotif = motif;
|
|
||||||
//
|
|
||||||
// Actions.runBlocking(
|
|
||||||
// new ParallelAction(
|
|
||||||
// manageFlywheelAuto(
|
|
||||||
// shoot3Time,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501
|
|
||||||
// ),
|
|
||||||
// shoot3.build(),
|
|
||||||
// prepareShootAll(colorSenseTime, shoot3Time, motif)
|
|
||||||
// )
|
|
||||||
// );
|
|
||||||
//
|
|
||||||
// Actions.runBlocking(
|
|
||||||
// new ParallelAction(
|
|
||||||
// manageShooterAuto(
|
|
||||||
// finalShootAllTime,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501,
|
|
||||||
// 0.501
|
|
||||||
// ),
|
|
||||||
// shootAllAuto(finalShootAllTime, finalSpindexerSpeedIncrease)
|
|
||||||
// )
|
|
||||||
//
|
|
||||||
// );
|
|
||||||
// }
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,839 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||||
|
public class Blue_V2 extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTagWebcam aprilTag;
|
||||||
|
|
||||||
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
|
public static double intake1Time = 2.9;
|
||||||
|
|
||||||
|
public static double intake2Time = 2.9;
|
||||||
|
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
|
||||||
|
boolean gpp = false;
|
||||||
|
|
||||||
|
boolean pgp = false;
|
||||||
|
|
||||||
|
boolean ppg = false;
|
||||||
|
|
||||||
|
double powPID = 0.0;
|
||||||
|
|
||||||
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
boolean spindexPosEqual(double spindexer) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex equal");
|
||||||
|
TELE.update();
|
||||||
|
return (scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) > spindexer - 0.01 &&
|
||||||
|
scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3) < spindexer + 0.01);
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double stamp2 = 0.0;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
targetVelocity = (double) vel;
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 16 == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||||
|
steady = true;
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished init");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action steadyShooter(int vel, boolean last) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
steady = flywheel.getSteady();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
|
||||||
|
if (last && !steady){
|
||||||
|
stamp = getRuntime();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
return false;
|
||||||
|
} else if (steady) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = getRuntime();
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (aprilTag.getTagById(21) != null) {
|
||||||
|
gpp = true;
|
||||||
|
} else if (aprilTag.getTagById(22) != null) {
|
||||||
|
pgp = true;
|
||||||
|
} else if (aprilTag.getTagById(23) != null) {
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
aprilTag.update();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg){
|
||||||
|
robot.turr1.setPower(turret_blueClose);
|
||||||
|
robot.turr2.setPower(1 - turret_blueClose);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intakeReject() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
double position = 0.0;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 0.3){
|
||||||
|
return true;
|
||||||
|
}else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex (double spindexer, double vel){
|
||||||
|
return new Action() {
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.spin1.setPower(spindexer);
|
||||||
|
robot.spin2.setPower(1-spindexer);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
return !spindexPosEqual(spindexer);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(double vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
double currentPos = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double initPos = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (ticker % 8 == 0) {
|
||||||
|
currentPos = (double) robot.shooter1.getCurrentPosition() / 2048;
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
|
initPos = currentPos;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (vel - velo > 500 && ticker > 16) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - vel > 500 && ticker > 16){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else if (Math.abs(vel - velo) < 100 && ticker > 16){
|
||||||
|
double feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer+waitTransferOut && transferIn){
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double position = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 30) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
flywheel = new Flywheel();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTagWebcam();
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
||||||
|
|
||||||
|
aprilTag.init(robot, TELE);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto-= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.turr1.setPower(turret_detectBlueClose);
|
||||||
|
robot.turr2.setPower(1 - turret_detectBlueClose);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
ColorDetect(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
ColorDetect(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, (double) robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,771 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(preselectTeleOp = "TeleopV2")
|
||||||
|
public class Red_V2 extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
AprilTagWebcam aprilTag;
|
||||||
|
|
||||||
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
Servos servo;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
public static double intake1Time = 2.9;
|
||||||
|
|
||||||
|
public static double intake2Time = 2.9;
|
||||||
|
|
||||||
|
public static double colorDetect = 3.0;
|
||||||
|
|
||||||
|
boolean gpp = false;
|
||||||
|
|
||||||
|
boolean pgp = false;
|
||||||
|
|
||||||
|
boolean ppg = false;
|
||||||
|
|
||||||
|
double powPID = 0.0;
|
||||||
|
|
||||||
|
double bearing = 0.0;
|
||||||
|
|
||||||
|
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
||||||
|
|
||||||
|
public Action initShooter(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double stamp2 = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 16 == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
if (vel < velo && getRuntime() - stamp2 > 3.0 && !steady){
|
||||||
|
steady = true;
|
||||||
|
stamp2 = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else if (steady && getRuntime() - stamp2 > 1.5){
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished init");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action steadyShooter(int vel, boolean last) {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
steady = flywheel.getSteady();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
if (last && !steady){
|
||||||
|
stamp = getRuntime();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
return false;
|
||||||
|
} else if (steady) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Obelisk() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = getRuntime();
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (aprilTag.getTagById(21) != null) {
|
||||||
|
gpp = true;
|
||||||
|
} else if (aprilTag.getTagById(22) != null) {
|
||||||
|
pgp = true;
|
||||||
|
} else if (aprilTag.getTagById(23) != null) {
|
||||||
|
ppg = true;
|
||||||
|
}
|
||||||
|
aprilTag.update();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("21", gpp);
|
||||||
|
TELE.addData("22", pgp);
|
||||||
|
TELE.addData("23", ppg);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
if (gpp || pgp || ppg){
|
||||||
|
double turretPID = servo.setTurrPos(turret_redClose);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
return !servo.turretEqual(turret_redClose);
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action spindex (double spindexer, int vel){
|
||||||
|
return new Action() {
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
robot.spin1.setPower(spindexer);
|
||||||
|
robot.spin2.setPower(1-spindexer);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("spindex");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
return !servo.spinEqual(spindexer);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Shoot(int vel) {
|
||||||
|
return new Action() {
|
||||||
|
double transferStamp = 0.0;
|
||||||
|
int ticker = 1;
|
||||||
|
boolean transferIn = false;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shooting");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
detectTag();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("ticker", ticker);
|
||||||
|
TELE.update();
|
||||||
|
transferIn = true;
|
||||||
|
return true;
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer+waitTransferOut && transferIn){
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("shot once");
|
||||||
|
TELE.update();
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(double intakeTime) {
|
||||||
|
return new Action() {
|
||||||
|
double position = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Intaking");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
if ((s1D < 40.0 && s2D < 40.0 && s3D < 40.0) || getRuntime() - stamp > intakeTime) {
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intakeReject() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < 0.3){
|
||||||
|
return true;
|
||||||
|
}else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action ColorDetect() {
|
||||||
|
return new Action() {
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
double position = 0.0;
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (ticker == 0) {
|
||||||
|
stamp = getRuntime();
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.02;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.02;
|
||||||
|
}
|
||||||
|
robot.spin1.setPower(position);
|
||||||
|
robot.spin2.setPower(1 - position);
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
if (s1D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b1 = 2;
|
||||||
|
} else {
|
||||||
|
b1 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b2 = 2;
|
||||||
|
} else {
|
||||||
|
b2 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 30) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
b3 = 2;
|
||||||
|
} else {
|
||||||
|
b3 = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("Detecting");
|
||||||
|
TELE.addData("Distance 1", s1D);
|
||||||
|
TELE.addData("Distance 2", s2D);
|
||||||
|
TELE.addData("Distance 3", s3D);
|
||||||
|
TELE.addData("B1", b1);
|
||||||
|
TELE.addData("B2", b2);
|
||||||
|
TELE.addData("B3", b3);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
flywheel = new Flywheel();
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
||||||
|
0, 0, 0
|
||||||
|
));
|
||||||
|
|
||||||
|
aprilTag = new AprilTagWebcam();
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
||||||
|
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b);
|
||||||
|
|
||||||
|
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
||||||
|
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
||||||
|
|
||||||
|
aprilTag.init(robot, TELE);
|
||||||
|
|
||||||
|
while (opModeInInit()) {
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodAuto-= 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodAuto += 0.01;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPower(1 - spindexer_intakePos1);
|
||||||
|
|
||||||
|
aprilTag.update();
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addData("Turret Pos", servo.getTurrPos());
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
initShooter(AUTO_CLOSE_VEL),
|
||||||
|
Obelisk()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodAuto);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
intake(intake1Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
ColorDetect(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
intake(intake2Time)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
ColorDetect(),
|
||||||
|
steadyShooter(AUTO_CLOSE_VEL, true),
|
||||||
|
intakeReject()
|
||||||
|
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
powPID = flywheel.manageFlywheel(AUTO_CLOSE_VEL, robot.shooter1.getCurrentPosition());
|
||||||
|
velo = flywheel.getVelo();
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
shootingSequence();
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.addLine("finished");
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
sleep(2000);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void detectTag(){
|
||||||
|
AprilTagDetection d20 = aprilTag.getTagById(20);
|
||||||
|
AprilTagDetection d24 = aprilTag.getTagById(24);
|
||||||
|
|
||||||
|
if (d20 != null) {
|
||||||
|
bearing = d20.ftcPose.bearing;
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (d24 != null) {
|
||||||
|
bearing = d24.ftcPose.bearing;
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
}
|
||||||
|
double turretPos = servo.getTurrPos() - (bearing / 1300);
|
||||||
|
double turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void shootingSequence() {
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
if (gpp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (pgp) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence4();
|
||||||
|
TELE.addLine("sequence4");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence3();
|
||||||
|
TELE.addLine("sequence3");
|
||||||
|
}
|
||||||
|
} else if (ppg) {
|
||||||
|
if (b1 + b2 + b3 == 4) {
|
||||||
|
if (b1 == 2 && b2 - b3 == 0) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2 && b1 - b3 == 0) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2 && b1 - b2 == 0) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else if (b1 + b2 + b3 >= 5) {
|
||||||
|
if (b1 == 2) {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
} else if (b2 == 2) {
|
||||||
|
sequence5();
|
||||||
|
TELE.addLine("sequence5");
|
||||||
|
} else if (b3 == 2) {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence6();
|
||||||
|
TELE.addLine("sequence6");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sequence1();
|
||||||
|
TELE.addLine("sequence1");
|
||||||
|
}
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence1() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence2() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence3() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence4() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence5() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void sequence6() {
|
||||||
|
Actions.runBlocking(
|
||||||
|
new SequentialAction(
|
||||||
|
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL),
|
||||||
|
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
||||||
|
Shoot(AUTO_CLOSE_VEL)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,648 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.actions;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
|
||||||
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.spindexer_outtakeBall2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
|
||||||
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.utils.Targeting.turretInterpolate;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Drivetrain;
|
|
||||||
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;
|
|
||||||
|
|
||||||
import java.util.Objects;
|
|
||||||
|
|
||||||
public class Actions{
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
Servos servos;
|
|
||||||
Flywheel flywheel;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Spindexer spindexer;
|
|
||||||
Targeting targeting;
|
|
||||||
Targeting.Settings targetingSettings;
|
|
||||||
Turret turret;
|
|
||||||
private int driverSlotGreen = 0;
|
|
||||||
private int passengerSlotGreen = 0;
|
|
||||||
private int rearSlotGreen = 0;
|
|
||||||
private int mostGreenSlot = 0;
|
|
||||||
private double firstSpindexShootPos = spinStartPos;
|
|
||||||
private boolean shootForward = true;
|
|
||||||
public static double firstShootTime = 0.3;
|
|
||||||
public int motif = 0;
|
|
||||||
|
|
||||||
public Actions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur){
|
|
||||||
this.robot = rob;
|
|
||||||
this.drive = dri;
|
|
||||||
this.TELE = tel;
|
|
||||||
this.servos = ser;
|
|
||||||
this.flywheel = fly;
|
|
||||||
this.spindexer = spi;
|
|
||||||
this.targeting = tar;
|
|
||||||
this.targetingSettings = tS;
|
|
||||||
this.turret = tur;
|
|
||||||
}
|
|
||||||
public Action prepareShootAll(double colorSenseTime, double time, int motif_id) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
double spindexerWiggle = 0.01;
|
|
||||||
|
|
||||||
boolean decideGreenSlot = false;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.addData("motif", motif_id);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
|
||||||
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
|
|
||||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
|
||||||
|
|
||||||
spindexer.detectBalls(true, true);
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
driverSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
passengerSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
rearSlotGreen++;
|
|
||||||
}
|
|
||||||
|
|
||||||
spindexer.setIntakePower(1);
|
|
||||||
|
|
||||||
decideGreenSlot = true;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else if (decideGreenSlot) {
|
|
||||||
|
|
||||||
if (driverSlotGreen >= passengerSlotGreen && driverSlotGreen >= rearSlotGreen) {
|
|
||||||
mostGreenSlot = 3;
|
|
||||||
} else if (passengerSlotGreen >= driverSlotGreen && passengerSlotGreen >= rearSlotGreen) {
|
|
||||||
mostGreenSlot = 2;
|
|
||||||
} else {
|
|
||||||
mostGreenSlot = 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
decideGreenSlot = false;
|
|
||||||
|
|
||||||
if (motif_id == 21) {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
|
||||||
shootForward = true;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = false;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
}
|
|
||||||
} else if (motif_id == 22) {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = false;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (mostGreenSlot == 1) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
|
||||||
shootForward = true;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
|
||||||
shootForward = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
|
||||||
// TELE.addData("MostGreenSlot", mostGreenSlot);
|
|
||||||
// TELE.update();
|
|
||||||
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
|
||||||
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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();
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
spindexer.setIntakePower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.setIntakePower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
if ((System.currentTimeMillis() - stamp < shootTime && servos.getSpinPos() < spinEndPos) || shooterTicker == 0) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servos.spinEqual(spinStartPos)) {
|
|
||||||
servos.setSpinPos(spinStartPos);
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = servos.getSpinCmdPos();
|
|
||||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
|
|
||||||
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();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
spindexer.setIntakePower(-0.3);
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = System.currentTimeMillis();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
spindexer.setIntakePower(0);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - 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
|
|
||||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
|
|
||||||
if (System.currentTimeMillis() - stamp < shootTime) {
|
|
||||||
|
|
||||||
if (System.currentTimeMillis() - stamp < firstShootTime) {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = servos.getSpinCmdPos();
|
|
||||||
|
|
||||||
if (shootForward) {
|
|
||||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
|
||||||
} else {
|
|
||||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
|
|
||||||
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();
|
|
||||||
spindexer.setIntakePower(1);
|
|
||||||
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Full?", spindexer.isFull());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return ((System.currentTimeMillis() - stamp) < (intakeTime * 1000)) && !spindexer.isFull();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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();
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
motif = turret.detectObelisk();
|
|
||||||
|
|
||||||
turret.setTurret(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();
|
|
||||||
|
|
||||||
if (shouldFinish){
|
|
||||||
if (redAlliance){
|
|
||||||
robot.limelight.pipelineSwitch(4);
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(2);
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
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++;
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
servos.setHoodPos(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);
|
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
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);
|
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
|
||||||
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;
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.autonomous;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -1,919 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bShootY;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bhPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bxPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.byPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rShootH;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rShootX;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rShootY;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rhPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rxPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ryPrep;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_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.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
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;
|
|
||||||
|
|
||||||
@Disabled
|
|
||||||
@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 = 17;
|
|
||||||
// ---- 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.setTurret(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();
|
|
||||||
|
|
||||||
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();
|
|
||||||
|
|
||||||
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.setTurret(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(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(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(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);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -1,804 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.autonomous.disabled;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bh4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.bx4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.by4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rh4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.rx4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry2a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry2b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry3a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry3b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry4a;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.ry4b;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodAuto;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_blueClose;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turret_redClose;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.AUTO_CLOSE_VEL;
|
|
||||||
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinPow;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
import com.acmerobotics.roadrunner.ParallelAction;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.acmerobotics.roadrunner.SequentialAction;
|
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
|
||||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
|
||||||
|
|
||||||
import java.util.List;
|
|
||||||
@Disabled
|
|
||||||
@Config
|
|
||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
|
||||||
public class ProtoAutoClose_V3 extends LinearOpMode {
|
|
||||||
public static double intake1Time = 2.7;
|
|
||||||
public static double intake2Time = 3.0;
|
|
||||||
public static double colorDetect = 3.0;
|
|
||||||
public static double holdTurrPow = 0.01; // power to hold turret in place
|
|
||||||
public static double slowSpeed = 30.0;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Flywheel flywheel;
|
|
||||||
Servos servo;
|
|
||||||
double velo = 0.0;
|
|
||||||
boolean gpp = false;
|
|
||||||
boolean pgp = false;
|
|
||||||
boolean ppg = false;
|
|
||||||
public static double spinUnjamTime = 0.6;
|
|
||||||
double powPID = 0.0;
|
|
||||||
double bearing = 0.0;
|
|
||||||
int b1 = 0; // 0 = no ball, 1 = green, 2 = purple
|
|
||||||
int b2 = 0;// 0 = no ball, 1 = green, 2 = purple
|
|
||||||
int b3 = 0;// 0 = no ball, 1 = green, 2 = purple
|
|
||||||
|
|
||||||
public Action initShooter(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return !flywheel.getSteady();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action Obelisk() {
|
|
||||||
return new Action() {
|
|
||||||
int id = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
|
||||||
if (result != null && result.isValid()) {
|
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
|
||||||
id = fiducial.getFiducialId();
|
|
||||||
TELE.addData("ID", id);
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (id == 21) {
|
|
||||||
gpp = true;
|
|
||||||
} else if (id == 22) {
|
|
||||||
pgp = true;
|
|
||||||
} else if (id == 23) {
|
|
||||||
ppg = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addData("21", gpp);
|
|
||||||
TELE.addData("22", pgp);
|
|
||||||
TELE.addData("23", ppg);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (gpp || pgp || ppg) {
|
|
||||||
if (redAlliance) {
|
|
||||||
robot.limelight.pipelineSwitch(3);
|
|
||||||
robot.turr1.setPosition(turret_redClose);
|
|
||||||
robot.turr2.setPosition(1 - turret_redClose);
|
|
||||||
return false;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(2);
|
|
||||||
double turretPID = turret_blueClose;
|
|
||||||
robot.turr1.setPosition(turretPID);
|
|
||||||
robot.turr2.setPosition(1 - turretPID);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action spindex(double spindexer, int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double spinPID = 0.0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
|
||||||
robot.spin1.setPosition(spinPID);
|
|
||||||
robot.spin2.setPosition(-spinPID);
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("spindex");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (servo.spinEqual(spindexer)) {
|
|
||||||
robot.spin1.setPosition(0);
|
|
||||||
robot.spin2.setPosition(0);
|
|
||||||
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
public Action Shoot(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
int ticker = 1;
|
|
||||||
double initPos = 0.0;
|
|
||||||
double finalPos = 0.0;
|
|
||||||
boolean zeroNeeded = false;
|
|
||||||
boolean zeroPassed = false;
|
|
||||||
double currentPos = 0.0;
|
|
||||||
double prevPos = 0.0;
|
|
||||||
double stamp = 0.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 < 2.7) {
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
|
|
||||||
robot.spin1.setPosition(-spinPow);
|
|
||||||
robot.spin2.setPosition(spinPow);
|
|
||||||
return true;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action spindexUnjam(double jamTime) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
if (ticker == 1) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ticker % 12 < 6) {
|
|
||||||
|
|
||||||
robot.spin1.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (getRuntime() - stamp > jamTime+0.4) {
|
|
||||||
|
|
||||||
robot.intake.setPower(0.5);
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
else if (getRuntime() - stamp > jamTime) {
|
|
||||||
|
|
||||||
robot.intake.setPower(-(getRuntime()-stamp-jamTime)*2.5);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
else {
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
double spinCurrentPos = 0.0;
|
|
||||||
double spinInitPos = 0.0;
|
|
||||||
boolean reverse = false;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
if (ticker % 60 < 12) {
|
|
||||||
|
|
||||||
robot.spin1.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
|
|
||||||
} else if (ticker % 60 < 30) {
|
|
||||||
robot.spin1.setPosition(-0.5);
|
|
||||||
robot.spin2.setPosition(0.5);
|
|
||||||
}
|
|
||||||
else if (ticker % 60 < 42) {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
robot.spin1.setPosition(0.5);
|
|
||||||
robot.spin2.setPosition(-0.5);
|
|
||||||
}
|
|
||||||
robot.intake.setPower(1);
|
|
||||||
TELE.addData("Reverse?", reverse);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (getRuntime() - stamp > intakeTime) {
|
|
||||||
if (reverse) {
|
|
||||||
robot.spin1.setPosition(-1);
|
|
||||||
robot.spin2.setPosition(1);
|
|
||||||
} else {
|
|
||||||
robot.spin1.setPosition(1);
|
|
||||||
robot.spin2.setPosition(-1);
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
if (ticker % 4 == 0) {
|
|
||||||
spinCurrentPos = servo.getSpinPos();
|
|
||||||
reverse = Math.abs(spinCurrentPos - spinInitPos) < 0.03;
|
|
||||||
spinInitPos = spinCurrentPos;
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action ColorDetect(int vel) {
|
|
||||||
return new Action() {
|
|
||||||
double stamp = 0.0;
|
|
||||||
int ticker = 0;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
if (ticker == 0) {
|
|
||||||
stamp = getRuntime();
|
|
||||||
}
|
|
||||||
ticker++;
|
|
||||||
|
|
||||||
flywheel.manageFlywheel(vel);
|
|
||||||
velo = flywheel.getVelo();
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
|
||||||
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
if (s1D < 43) {
|
|
||||||
|
|
||||||
double green = robot.color1.getNormalizedColors().green;
|
|
||||||
double red = robot.color1.getNormalizedColors().red;
|
|
||||||
double blue = robot.color1.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b1 = 2;
|
|
||||||
} else {
|
|
||||||
b1 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s2D < 60) {
|
|
||||||
|
|
||||||
double green = robot.color2.getNormalizedColors().green;
|
|
||||||
double red = robot.color2.getNormalizedColors().red;
|
|
||||||
double blue = robot.color2.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b2 = 2;
|
|
||||||
} else {
|
|
||||||
b2 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (s3D < 33) {
|
|
||||||
|
|
||||||
double green = robot.color3.getNormalizedColors().green;
|
|
||||||
double red = robot.color3.getNormalizedColors().red;
|
|
||||||
double blue = robot.color3.getNormalizedColors().blue;
|
|
||||||
|
|
||||||
double gP = green / (green + red + blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
b3 = 2;
|
|
||||||
} else {
|
|
||||||
b3 = 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("Detecting");
|
|
||||||
TELE.addData("Distance 1", s1D);
|
|
||||||
TELE.addData("Distance 2", s2D);
|
|
||||||
TELE.addData("Distance 3", s3D);
|
|
||||||
TELE.addData("B1", b1);
|
|
||||||
TELE.addData("B2", b2);
|
|
||||||
TELE.addData("B3", b3);
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return (b1 + b2 + b3 < 4) && !(getRuntime() - stamp > colorDetect);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(
|
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
|
||||||
);
|
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(
|
|
||||||
0, 0, 0
|
|
||||||
));
|
|
||||||
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
|
|
||||||
robot.limelight.pipelineSwitch(1);
|
|
||||||
robot.limelight.start();
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
//
|
|
||||||
// TrajectoryActionBuilder lever = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
|
||||||
// .strafeToLinearHeading(new Vector2d(bx2c, by2c), bh2c);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
TrajectoryActionBuilder shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
TrajectoryActionBuilder pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
TrajectoryActionBuilder shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
while (opModeInInit()) {
|
|
||||||
|
|
||||||
if (gamepad2.dpadUpWasPressed()) {
|
|
||||||
hoodAuto -= 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.dpadDownWasPressed()) {
|
|
||||||
hoodAuto += 0.01;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
|
||||||
redAlliance = !redAlliance;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
double turretPID;
|
|
||||||
if (redAlliance) {
|
|
||||||
turretPID = turret_redClose;
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx2a, ry2a), rh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx2b, ry2b), rh2b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
// lever = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
|
||||||
// .strafeToLinearHeading(new Vector2d(rx2c, ry2c), rh2c);
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(rx2b, ry2b, rh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx3a, ry3a), rh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx3b, ry3b), rh3b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(rx3b, ry3b, rh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
pickup3 = drive.actionBuilder(new Pose2d(rx1, ry1, rh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx4a, ry4a), rh4a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx4b, ry4b), rh4b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
shoot3 = drive.actionBuilder(new Pose2d(rx4b, ry4b, rh4b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(rx1, ry1), rh1);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
turretPID = turret_blueClose;
|
|
||||||
|
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2a, by2a), bh2a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx2b, by2b), bh2b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(bx2b, by2b, bh2b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
pickup2 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3a, by3a), bh3a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx3b, by3b), bh3b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(bx3b, by3b, bh3b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
|
|
||||||
pickup3 = drive.actionBuilder(new Pose2d(bx1, by1, bh1))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx4a, by4a), bh4a)
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx4b, by4b), bh4b,
|
|
||||||
new TranslationalVelConstraint(slowSpeed));
|
|
||||||
shoot3 = drive.actionBuilder(new Pose2d(bx4b, by4b, bh4b))
|
|
||||||
.strafeToLinearHeading(new Vector2d(bx1, by1), bh1);
|
|
||||||
}
|
|
||||||
|
|
||||||
robot.turr1.setPosition(turretPID);
|
|
||||||
robot.turr2.setPosition(1 - turretPID);
|
|
||||||
|
|
||||||
robot.hood.setPosition(hoodAuto);
|
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
|
||||||
|
|
||||||
TELE.addData("Red?", redAlliance);
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot0.build(),
|
|
||||||
initShooter(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup1.build(),
|
|
||||||
intake(intake1Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
shoot1.build(),
|
|
||||||
spindexUnjam(spinUnjamTime)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup2.build(),
|
|
||||||
intake(intake2Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot2.build(),
|
|
||||||
spindexUnjam(spinUnjamTime)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
pickup3.build(),
|
|
||||||
intake(intake2Time)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
Actions.runBlocking(
|
|
||||||
new ParallelAction(
|
|
||||||
shoot3.build(),
|
|
||||||
spindexUnjam(spinUnjamTime)
|
|
||||||
|
|
||||||
)
|
|
||||||
);
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
shootingSequence();
|
|
||||||
|
|
||||||
robot.transfer.setPower(0);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
|
||||||
TELE.addLine("finished");
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
sleep(2000);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
//TODO: adjust this according to Teleop numbers
|
|
||||||
public void detectTag() {
|
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
bearing = result.getTx();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
double turretPos = (bearing / 1300);
|
|
||||||
robot.turr1.setPosition(turretPos);
|
|
||||||
robot.turr2.setPosition(1 - turretPos);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void shootingSequence() {
|
|
||||||
TELE.addLine("Shooting");
|
|
||||||
TELE.update();
|
|
||||||
Actions.runBlocking(Shoot(AUTO_CLOSE_VEL));
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence1() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence2() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence3() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence4() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence5() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void sequence6() {
|
|
||||||
Actions.runBlocking(
|
|
||||||
new SequentialAction(
|
|
||||||
spindex(spindexer_outtakeBall3, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall2, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL),
|
|
||||||
spindex(spindexer_outtakeBall1, AUTO_CLOSE_VEL),
|
|
||||||
Shoot(AUTO_CLOSE_VEL)
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,23 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Back_Poses {
|
|
||||||
public static double rLeaveX = 90, rLeaveY = 80, rLeaveH = 50.1;
|
|
||||||
public static double bLeaveX = 90, bLeaveY = -80, bLeaveH = -50;
|
|
||||||
|
|
||||||
public static double rShootX = 95, rShootY = 85, rShootH = 90;
|
|
||||||
public static double bShootX = 95, bShootY = -85, bShootH = -90;
|
|
||||||
|
|
||||||
public static double rStackPickupAX = 75, rStackPickupAY = 53, rStackPickupAH = 140;
|
|
||||||
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
|
|
||||||
|
|
||||||
public static double rStackPickupBX = 50, rStackPickupBY = 78, rStackPickupBH = 140.1;
|
|
||||||
public static double bStackPickupBX = 50, bStackPickupBY = -78, bStackPickupBH = -140.1;
|
|
||||||
|
|
||||||
public static Pose2d autoStart = new Pose2d(0, 0, 0); // TODO: find this position
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -1,16 +1,5 @@
|
|||||||
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 LightGreen = 0.5;
|
|
||||||
public static double LightPurple = 0.715;
|
|
||||||
public static double LightOrange = 0.33;
|
|
||||||
public static double LightRed = 0.28;
|
|
||||||
public static double LightBlue = 0.6;
|
|
||||||
|
|
||||||
public static double colorFilterAlpha = 1;
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,46 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public class Front_Poses {
|
|
||||||
|
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
|
|
||||||
public static double bx1 = 20, by1 = 0.5, bh1 = 0.1;
|
|
||||||
|
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
|
||||||
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
|
||||||
|
|
||||||
public static double rx2b = 23, ry2b = 36, rh2b = 140.1;
|
|
||||||
public static double bx2b = 19, by2b = -40, bh2b = -140.1;
|
|
||||||
|
|
||||||
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
|
||||||
public static double bx3a = 55, by3a = -39, bh3a = -140;
|
|
||||||
|
|
||||||
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
|
||||||
public static double bx3aG = 55, by3aG = -43, bh3aG = -140;
|
|
||||||
|
|
||||||
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
|
||||||
public static double bx3b = 41, by3b = -59, bh3b = -140.1;
|
|
||||||
|
|
||||||
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
|
||||||
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
|
||||||
|
|
||||||
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
|
||||||
public static double bx4b = 47, by4b = -85, bh4b = -140.1;
|
|
||||||
|
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
|
||||||
|
|
||||||
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
|
||||||
public static double bShootX = 40, bShootY = 0, bShootH = -50;
|
|
||||||
|
|
||||||
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
|
|
||||||
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
|
|
||||||
|
|
||||||
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 50;
|
|
||||||
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -50;
|
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,33 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class Poses {
|
||||||
|
|
||||||
|
public static double goalHeight = 42; //in inches
|
||||||
|
|
||||||
|
public static double turretHeight = 12;
|
||||||
|
|
||||||
|
public static double relativeGoalHeight = goalHeight - turretHeight;
|
||||||
|
|
||||||
|
public static Pose2d goalPose = new Pose2d(-15, 0, 0);
|
||||||
|
|
||||||
|
public static double rx1 = 45, ry1 = -7, rh1 = 0;
|
||||||
|
public static double rx2a = 45, ry2a = 5, rh2a = Math.toRadians(140);
|
||||||
|
public static double rx2b = 31, ry2b = 32, rh2b = Math.toRadians(140);
|
||||||
|
public static double rx3a = 58, ry3a = 42, rh3a = Math.toRadians(140);
|
||||||
|
public static double rx3b = 34, ry3b = 58, rh3b = Math.toRadians(140);
|
||||||
|
|
||||||
|
public static double bx1 = 45, by1 = 6, bh1 = 0;
|
||||||
|
public static double bx2a = 53, by2a = -7, bh2a = Math.toRadians(-140);
|
||||||
|
public static double bx2b = 23, by2b = -39, bh2b = Math.toRadians(-140);
|
||||||
|
public static double bx3a = 56, by3a = -34, bh3a = Math.toRadians(-140);
|
||||||
|
public static double bx3b = 34, by3b = -58, bh3b = Math.toRadians(-140);
|
||||||
|
|
||||||
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
||||||
|
|
||||||
|
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1);
|
||||||
|
|
||||||
|
}
|
||||||
@@ -1,21 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
|
|
||||||
@Disabled
|
|
||||||
@Config
|
|
||||||
public class Poses_V2 {
|
|
||||||
|
|
||||||
public static double rXGateA = 35.5, rYGateA = 46.5, rHGateA = 2.7;
|
|
||||||
|
|
||||||
public static double rXGateB = 56, rYGateB = 37, rHGateB = 2.7750735106709836;
|
|
||||||
|
|
||||||
public static double rXGate = 28, rYGate = 65, rHGate = Math.toRadians(179);
|
|
||||||
|
|
||||||
public static double bXGateA = 35.5, bYGateA = -46.5, bHGateA = -2.7;
|
|
||||||
public static double bXGateB = 56, bYGateB = -37, bHGateB = -2.7750735106709836;
|
|
||||||
|
|
||||||
public static double bXGate = 28, bYGate = -65, bHGate = Math.toRadians(-179);
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -5,41 +5,41 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.07; //0.13;
|
public static double spindexer_intakePos1 = 0.34;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.27; //0.33;//0.5;
|
public static double spindexer_intakePos2 = 0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.46; //0.53;//0.66;
|
public static double spindexer_intakePos3 = 0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
|
public static double spindexer_outtakeBall3 = 0.42;
|
||||||
public static double spindexer_outtakeBall3b = 0.15; //0.65; //0.24;
|
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
public static double spindexer_outtakeBall2 = 0.74;
|
||||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
public static double spindexer_outtakeBall1 = 0.58;
|
||||||
public static double spinStartPos = 0.22;
|
|
||||||
public static double spinEndPos = 0.85;
|
|
||||||
|
|
||||||
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
|
||||||
|
|
||||||
public static double transferServo_out = 0.15;
|
public static double transferServo_out = 0.15;
|
||||||
|
|
||||||
public static double transferServo_in = 0.38;
|
public static double transferServo_in = 0.38;
|
||||||
|
|
||||||
public static double hoodAuto = 0.27;
|
public static double turret_range = 0.9;
|
||||||
|
|
||||||
public static double hoodOffset = -0.05;
|
public static double hoodDefault = 0.6;
|
||||||
|
|
||||||
|
public static double hoodAuto = 0.55;
|
||||||
|
|
||||||
|
public static double hoodAutoFar = 0.5; //TODO: change this;
|
||||||
|
|
||||||
|
public static double hoodHigh = 0.21; //TODO: change this;
|
||||||
|
|
||||||
|
public static double hoodLow = 1.0; //TODO: change this;
|
||||||
|
|
||||||
public static double turret_redClose = 0.42;
|
public static double turret_redClose = 0.42;
|
||||||
public static double turret_blueClose = 0.38;
|
public static double turret_blueClose = 0.38;
|
||||||
|
public static double turret_redFar = 0.5; //TODO: change this
|
||||||
|
public static double turret_blueFar = 0.5; // TODO: change this
|
||||||
|
|
||||||
// These values are ADDED to turrDefault
|
public static double turret_detectRedClose = 0.2;
|
||||||
public static double redObeliskTurrPos1 = 0.12;
|
|
||||||
public static double redObeliskTurrPos2 = 0.13;
|
public static double turret_detectBlueClose = 0.6;
|
||||||
public static double redObeliskTurrPos3 = 0.14;
|
public static double turrDefault = 0.40;
|
||||||
public static double blueObeliskTurrPos1 = -0.12;
|
|
||||||
public static double blueObeliskTurrPos2 = -0.13;
|
|
||||||
public static double blueObeliskTurrPos3 = -0.14;
|
|
||||||
public static double redTurretShootPos = 0.1;
|
|
||||||
public static double blueTurretShootPos = -0.14;
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,13 +1,24 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
|
|
||||||
@Disabled
|
|
||||||
@Config
|
@Config
|
||||||
public class ShooterVars {
|
public class ShooterVars {
|
||||||
|
public static double turret_GearRatio = 0.9974;
|
||||||
|
|
||||||
|
public static double turret_Range = 355;
|
||||||
|
|
||||||
|
public static int velTolerance = 300;
|
||||||
|
|
||||||
|
public static int initTolerance = 1000;
|
||||||
|
|
||||||
|
public static int maxVel = 4500;
|
||||||
|
public static double waitTransferOut = 0.3;
|
||||||
|
public static double waitTransfer = 0.4;
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
|
||||||
// VELOCITY CONSTANTS
|
// VELOCITY CONSTANTS
|
||||||
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
public static int AUTO_CLOSE_VEL = 3025; //3300;
|
||||||
|
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||||
}
|
}
|
||||||
@@ -1,19 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
|
||||||
|
|
||||||
public class StateEnums {
|
|
||||||
public enum Motif {
|
|
||||||
NONE,
|
|
||||||
GPP, // Green, Purple, Purple
|
|
||||||
PGP, // Purple, Green, Purple
|
|
||||||
PPG // Purple, Purple, Green
|
|
||||||
}
|
|
||||||
|
|
||||||
public enum LightState {
|
|
||||||
BALL_COUNT,
|
|
||||||
BALL_COLOR,
|
|
||||||
GOAL_LOCK,
|
|
||||||
MANUAL,
|
|
||||||
DISABLED,
|
|
||||||
OFF
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.disabled;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -185,19 +185,19 @@ public final class MecanumDrive {
|
|||||||
new DualNum<Time>(new double[]{
|
new DualNum<Time>(new double[]{
|
||||||
(leftFrontPosVel.position - lastLeftFrontPos),
|
(leftFrontPosVel.position - lastLeftFrontPos),
|
||||||
leftFrontPosVel.velocity,
|
leftFrontPosVel.velocity,
|
||||||
}).times(PARAMS.inPerTick),
|
}).times(PARAMS.inPerTick),
|
||||||
new DualNum<Time>(new double[]{
|
new DualNum<Time>(new double[]{
|
||||||
(leftBackPosVel.position - lastLeftBackPos),
|
(leftBackPosVel.position - lastLeftBackPos),
|
||||||
leftBackPosVel.velocity,
|
leftBackPosVel.velocity,
|
||||||
}).times(PARAMS.inPerTick),
|
}).times(PARAMS.inPerTick),
|
||||||
new DualNum<Time>(new double[]{
|
new DualNum<Time>(new double[]{
|
||||||
(rightBackPosVel.position - lastRightBackPos),
|
(rightBackPosVel.position - lastRightBackPos),
|
||||||
rightBackPosVel.velocity,
|
rightBackPosVel.velocity,
|
||||||
}).times(PARAMS.inPerTick),
|
}).times(PARAMS.inPerTick),
|
||||||
new DualNum<Time>(new double[]{
|
new DualNum<Time>(new double[]{
|
||||||
(rightFrontPosVel.position - lastRightFrontPos),
|
(rightFrontPosVel.position - lastRightFrontPos),
|
||||||
rightFrontPosVel.velocity,
|
rightFrontPosVel.velocity,
|
||||||
}).times(PARAMS.inPerTick)
|
}).times(PARAMS.inPerTick)
|
||||||
));
|
));
|
||||||
|
|
||||||
lastLeftFrontPos = leftFrontPosVel.position;
|
lastLeftFrontPos = leftFrontPosVel.position;
|
||||||
|
|||||||
@@ -0,0 +1,903 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.tests.PIDServoTest.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.qualcomm.hardware.lynx.LynxModule;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
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.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class TeleopV2 extends LinearOpMode {
|
||||||
|
Servos servo;
|
||||||
|
Flywheel flywheel;
|
||||||
|
public static double manualVel = 3000;
|
||||||
|
public static double hood = 0.5;
|
||||||
|
public static double hoodDefaultPos = 0.5;
|
||||||
|
public static double desiredTurretAngle = 180;
|
||||||
|
public static double velMultiplier = 20;
|
||||||
|
public static double shootStamp2 = 0.0;
|
||||||
|
|
||||||
|
public double vel = 3000;
|
||||||
|
public boolean autoVel = true;
|
||||||
|
public double manualOffset = 0.0;
|
||||||
|
public boolean autoHood = true;
|
||||||
|
public boolean green1 = false;
|
||||||
|
public boolean green2 = false;
|
||||||
|
public boolean green3 = false;
|
||||||
|
public double shootStamp = 0.0;
|
||||||
|
public boolean circle = false;
|
||||||
|
public boolean square = false;
|
||||||
|
public boolean triangle = false;
|
||||||
|
double autoHoodOffset = 0.0;
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
boolean intake = false;
|
||||||
|
boolean reject = false;
|
||||||
|
double xOffset = 0.0;
|
||||||
|
double yOffset = 0.0;
|
||||||
|
double headingOffset = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
int camTicker = 0;
|
||||||
|
List<Double> s1G = new ArrayList<>();
|
||||||
|
List<Double> s2G = new ArrayList<>();
|
||||||
|
List<Double> s3G = new ArrayList<>();
|
||||||
|
List<Double> s1T = new ArrayList<>();
|
||||||
|
List<Double> s2T = new ArrayList<>();
|
||||||
|
List<Double> s3T = new ArrayList<>();
|
||||||
|
List<Boolean> s1 = new ArrayList<>();
|
||||||
|
List<Boolean> s2 = new ArrayList<>();
|
||||||
|
List<Boolean> s3 = new ArrayList<>();
|
||||||
|
boolean oddBallColor = false;
|
||||||
|
AprilTagWebcam aprilTagWebcam = new AprilTagWebcam();
|
||||||
|
MecanumDrive drive;
|
||||||
|
double hoodOffset = 0.0;
|
||||||
|
boolean shoot1 = false;
|
||||||
|
// Make these class-level flags
|
||||||
|
boolean shootA = true;
|
||||||
|
boolean shootB = true;
|
||||||
|
boolean shootC = true;
|
||||||
|
boolean manualTurret = false;
|
||||||
|
|
||||||
|
boolean outtake1 = false;
|
||||||
|
boolean outtake2 = false;
|
||||||
|
boolean outtake3 = false;
|
||||||
|
boolean overrideTurr = false;
|
||||||
|
|
||||||
|
List<Integer> shootOrder = new ArrayList<>();
|
||||||
|
boolean emergency = false;
|
||||||
|
private double lastEncoderRevolutions = 0.0;
|
||||||
|
private double lastTimeStamp = 0.0;
|
||||||
|
private double velo1, velo;
|
||||||
|
private double stamp1, stamp, initPos;
|
||||||
|
private boolean shootAll = false;
|
||||||
|
private double transferStamp = 0.0;
|
||||||
|
private int tickerA = 1;
|
||||||
|
private boolean transferIn = false;
|
||||||
|
double turretPID = 0.0;
|
||||||
|
double turretPos = 0.5;
|
||||||
|
double spindexPID = 0.0;
|
||||||
|
double spindexPos = spindexer_intakePos1;
|
||||||
|
double error = 0.0;
|
||||||
|
|
||||||
|
public static double velPrediction(double distance) {
|
||||||
|
|
||||||
|
if (distance < 30) {
|
||||||
|
return 2750;
|
||||||
|
} else if (distance > 100) {
|
||||||
|
if (distance > 160) {
|
||||||
|
return 4200;
|
||||||
|
}
|
||||||
|
return 3700;
|
||||||
|
} else {
|
||||||
|
// linear interpolation between 40->2650 and 120->3600
|
||||||
|
double slope = (3700.0 - 2750.0) / (100.0 - 30);
|
||||||
|
return (int) Math.round(2750 + slope * (distance - 30));
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
|
||||||
|
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
servo = new Servos(hardwareMap);
|
||||||
|
flywheel = new Flywheel();
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
Pose2d shootPos = teleStart;
|
||||||
|
|
||||||
|
aprilTagWebcam.init(new Robot(hardwareMap), TELE);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
//DRIVETRAIN:
|
||||||
|
|
||||||
|
double y = -gamepad1.right_stick_y; // Remember, Y stick value is reversed
|
||||||
|
double x = gamepad1.right_stick_x * 1.1; // Counteract imperfect strafing
|
||||||
|
double rx = gamepad1.left_stick_x;
|
||||||
|
|
||||||
|
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||||
|
double frontLeftPower = (y + x + rx) / denominator;
|
||||||
|
double backLeftPower = (y - x + rx) / denominator;
|
||||||
|
double frontRightPower = (y - x - rx) / denominator;
|
||||||
|
double backRightPower = (y + x - rx) / denominator;
|
||||||
|
|
||||||
|
robot.frontLeft.setPower(frontLeftPower);
|
||||||
|
robot.backLeft.setPower(backLeftPower);
|
||||||
|
robot.frontRight.setPower(frontRightPower);
|
||||||
|
robot.backRight.setPower(backRightPower);
|
||||||
|
|
||||||
|
// PID SERVOS
|
||||||
|
turretPID = servo.setTurrPos(turretPos);
|
||||||
|
robot.turr1.setPower(turretPID);
|
||||||
|
robot.turr2.setPower(-turretPID);
|
||||||
|
|
||||||
|
//TODO: make sure changing position works throughout opmode
|
||||||
|
if (!servo.spinEqual(spindexPos)){
|
||||||
|
spindexPID = servo.setSpinPos(spindexPos);
|
||||||
|
robot.spin1.setPower(spindexPID);
|
||||||
|
robot.spin2.setPower(-spindexPID);
|
||||||
|
} else{
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
//INTAKE:
|
||||||
|
|
||||||
|
if (gamepad1.rightBumperWasPressed()) {
|
||||||
|
intake = !intake;
|
||||||
|
reject = false;
|
||||||
|
shootAll = false;
|
||||||
|
emergency = false;
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad1.leftBumperWasPressed()) {
|
||||||
|
intake = false;
|
||||||
|
emergency = !emergency;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake) {
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) > 0.15) {
|
||||||
|
spindexPos = spindexer_intakePos1 + 0.015;
|
||||||
|
} else {
|
||||||
|
spindexPos = spindexer_intakePos1 - 0.015;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (reject) {
|
||||||
|
robot.intake.setPower(-1);
|
||||||
|
spindexPos = spindexer_intakePos1;
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
//COLOR:
|
||||||
|
|
||||||
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
double s3D = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
if (s1D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s1G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s1.add(true);
|
||||||
|
} else {
|
||||||
|
s1.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s1T.add(getRuntime());
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s2D < 40) {
|
||||||
|
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s2G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s2.add(true);
|
||||||
|
} else {
|
||||||
|
s2.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s2T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s3D < 30) {
|
||||||
|
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
s3G.add(gP);
|
||||||
|
|
||||||
|
if (gP >= 0.43) {
|
||||||
|
s3.add(true);
|
||||||
|
} else {
|
||||||
|
s3.add(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
s3T.add(getRuntime());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!s1.isEmpty()) {
|
||||||
|
green1 = checkGreen(s1, s1T);
|
||||||
|
}
|
||||||
|
if (!s2.isEmpty()) {
|
||||||
|
green2 = checkGreen(s2, s2T);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (!s3.isEmpty()) {
|
||||||
|
green3 = checkGreen(s3, s3T);
|
||||||
|
}
|
||||||
|
|
||||||
|
//SHOOTER:
|
||||||
|
|
||||||
|
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
||||||
|
|
||||||
|
robot.shooter1.setPower(powPID);
|
||||||
|
robot.shooter2.setPower(powPID);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
//TURRET:
|
||||||
|
|
||||||
|
double offset;
|
||||||
|
|
||||||
|
double robX = drive.localizer.getPose().position.x;
|
||||||
|
double robY = drive.localizer.getPose().position.y;
|
||||||
|
|
||||||
|
double robotX = robX - xOffset;
|
||||||
|
double robotY = robY - yOffset;
|
||||||
|
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||||
|
|
||||||
|
double goalX = -10;
|
||||||
|
double goalY = 0;
|
||||||
|
|
||||||
|
double dx = goalX - robotX; // delta x from robot to goal
|
||||||
|
double dy = goalY - robotY; // delta y from robot to goal
|
||||||
|
|
||||||
|
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
|
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
||||||
|
|
||||||
|
desiredTurretAngle += manualOffset;
|
||||||
|
|
||||||
|
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||||
|
|
||||||
|
if (offset > 135) {
|
||||||
|
offset -= 360;
|
||||||
|
}
|
||||||
|
|
||||||
|
//TODO: test the camera teleop code
|
||||||
|
double pos = turrDefault + (error/8); // adds the overall error to the default
|
||||||
|
|
||||||
|
TELE.addData("offset", offset);
|
||||||
|
|
||||||
|
pos -= offset * (0.9 / 360);
|
||||||
|
|
||||||
|
if (pos < 0.02) {
|
||||||
|
pos = 0.02;
|
||||||
|
} else if (pos > 0.97) {
|
||||||
|
pos = 0.97;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (y < 0.1 && y > -0.1 && x < 0.1 && x > -0.1 && rx < 0.1 && rx > -0.1){ //not moving
|
||||||
|
AprilTagDetection d20 = aprilTagWebcam.getTagById(20);
|
||||||
|
AprilTagDetection d24 = aprilTagWebcam.getTagById(24);
|
||||||
|
|
||||||
|
double bearing = 0.0;
|
||||||
|
if (d20 != null || d24 != null){
|
||||||
|
if (d20 != null) {
|
||||||
|
bearing = d20.ftcPose.bearing;
|
||||||
|
}
|
||||||
|
if (d24 != null) {
|
||||||
|
bearing = d24.ftcPose.bearing;
|
||||||
|
}
|
||||||
|
overrideTurr = true;
|
||||||
|
turretPos = servo.getTurrPos() - (bearing/1300);
|
||||||
|
TELE.addData("Bear", bearing);
|
||||||
|
|
||||||
|
double bearingCorrection = bearing / 1300;
|
||||||
|
|
||||||
|
|
||||||
|
// deadband: ignore tiny noise
|
||||||
|
if (Math.abs(bearing) > 0.3 && camTicker < 8) {
|
||||||
|
|
||||||
|
// only accumulate if bearing direction is consistent
|
||||||
|
if (Math.signum(bearingCorrection) == Math.signum(error) || error == 0) {
|
||||||
|
error += bearingCorrection;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
camTicker++;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
} else {
|
||||||
|
camTicker = 0;
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (manualTurret) {
|
||||||
|
pos = turrDefault + (manualOffset / 100);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!overrideTurr) {
|
||||||
|
turretPos = pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpad_right) {
|
||||||
|
manualOffset -= 2;
|
||||||
|
} else if (gamepad2.dpad_left) {
|
||||||
|
manualOffset += 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
//VELOCITY AUTOMATIC
|
||||||
|
|
||||||
|
if (autoVel) {
|
||||||
|
vel = velPrediction(distanceToGoal);
|
||||||
|
} else {
|
||||||
|
vel = manualVel;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.right_stick_button) {
|
||||||
|
autoVel = true;
|
||||||
|
} else if (gamepad2.right_stick_y < -0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 4100;
|
||||||
|
} else if (gamepad2.right_stick_y > 0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 2700;
|
||||||
|
} else if (gamepad2.right_stick_x > 0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 3600;
|
||||||
|
} else if (gamepad2.right_stick_x < -0.5) {
|
||||||
|
autoVel = false;
|
||||||
|
manualVel = 3100;
|
||||||
|
}
|
||||||
|
|
||||||
|
//HOOD:
|
||||||
|
|
||||||
|
if (autoHood) {
|
||||||
|
robot.hood.setPosition(hoodAnglePrediction(distanceToGoal) + autoHoodOffset);
|
||||||
|
} else {
|
||||||
|
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.dpadUpWasPressed()) {
|
||||||
|
hoodOffset -= 0.03;
|
||||||
|
autoHoodOffset -= 0.02;
|
||||||
|
|
||||||
|
} else if (gamepad2.dpadDownWasPressed()) {
|
||||||
|
hoodOffset += 0.03;
|
||||||
|
autoHoodOffset += 0.02;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_x > 0.5) {
|
||||||
|
manualTurret = false;
|
||||||
|
} else if (gamepad2.left_stick_x < -0.5) {
|
||||||
|
manualOffset = 0;
|
||||||
|
manualTurret = false;
|
||||||
|
if (gamepad2.left_bumper) {
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(2, 0, 0));
|
||||||
|
sleep(1200);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_y < -0.5) {
|
||||||
|
autoHood = true;
|
||||||
|
} else if (gamepad2.left_stick_y > 0.5) {
|
||||||
|
autoHood = false;
|
||||||
|
hoodOffset = 0;
|
||||||
|
if (gamepad2.left_bumper) {
|
||||||
|
xOffset = robotX;
|
||||||
|
yOffset = robotY;
|
||||||
|
headingOffset = robotHeading;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//SHOOT ALL:]
|
||||||
|
|
||||||
|
if (emergency) {
|
||||||
|
intake = false;
|
||||||
|
reject = true;
|
||||||
|
|
||||||
|
if (getRuntime() % 3 > 1.5) {
|
||||||
|
spindexPos = 1;
|
||||||
|
} else {
|
||||||
|
spindexPos = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
} else if (shootAll) {
|
||||||
|
|
||||||
|
TELE.addData("100% works", shootOrder);
|
||||||
|
|
||||||
|
intake = false;
|
||||||
|
reject = false;
|
||||||
|
|
||||||
|
if (!shootOrder.isEmpty() && (getRuntime() - shootStamp < 12)) {
|
||||||
|
int currentSlot = shootOrder.get(0); // Peek, do NOT remove yet
|
||||||
|
boolean shootingDone = false;
|
||||||
|
|
||||||
|
if (!outtake1) {
|
||||||
|
outtake1 = (servo.spinEqual(spindexer_outtakeBall1));
|
||||||
|
}
|
||||||
|
if (!outtake2) {
|
||||||
|
outtake2 = (servo.spinEqual(spindexer_outtakeBall2));
|
||||||
|
}
|
||||||
|
if (!outtake3) {
|
||||||
|
outtake3 = (servo.spinEqual(spindexer_outtakeBall3));
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (currentSlot) {
|
||||||
|
case 1:
|
||||||
|
shootA = shootTeleop(spindexer_outtakeBall1, outtake1, shootStamp2);
|
||||||
|
TELE.addData("shootA", shootA);
|
||||||
|
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootA;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
shootB = shootTeleop(spindexer_outtakeBall2, outtake2, shootStamp2);
|
||||||
|
TELE.addData("shootB", shootB);
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootB;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
shootC = shootTeleop(spindexer_outtakeBall3, outtake3, shootStamp2);
|
||||||
|
TELE.addData("shootC", shootC);
|
||||||
|
if ((getRuntime() - shootStamp) < 4 * (4 - shootOrder.size())) {
|
||||||
|
shootingDone = !shootC;
|
||||||
|
} else {
|
||||||
|
shootingDone = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Remove from the list only if shooting is complete
|
||||||
|
if (shootingDone) {
|
||||||
|
shootOrder.remove(0);
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// Finished shooting all balls
|
||||||
|
spindexPos = spindexer_intakePos1;
|
||||||
|
shootA = true;
|
||||||
|
shootB = true;
|
||||||
|
shootC = true;
|
||||||
|
reject = false;
|
||||||
|
intake = true;
|
||||||
|
shootAll = false;
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
overrideTurr = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.squareWasPressed()) {
|
||||||
|
square = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.circleWasPressed()) {
|
||||||
|
circle = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.triangleWasPressed()) {
|
||||||
|
triangle = true;
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootStamp2 = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (square || circle || triangle) {
|
||||||
|
|
||||||
|
// Count green balls
|
||||||
|
int greenCount = 0;
|
||||||
|
if (green1) greenCount++;
|
||||||
|
if (green2) greenCount++;
|
||||||
|
if (green3) greenCount++;
|
||||||
|
|
||||||
|
// Determine the odd ball color
|
||||||
|
oddBallColor = greenCount < 2; // true = green, false = purple
|
||||||
|
|
||||||
|
shootOrder.clear();
|
||||||
|
|
||||||
|
// Determine shooting order based on button pressed
|
||||||
|
// square = odd ball first, triangle = odd ball second, circle = odd ball third
|
||||||
|
if (square) {
|
||||||
|
// Odd ball first
|
||||||
|
addOddThenRest(shootOrder, oddBallColor);
|
||||||
|
|
||||||
|
} else if (triangle) {
|
||||||
|
// Odd ball second
|
||||||
|
addOddInMiddle(shootOrder, oddBallColor);
|
||||||
|
} else if (circle) {
|
||||||
|
// Odd ball last
|
||||||
|
addOddLast(shootOrder, oddBallColor);
|
||||||
|
}
|
||||||
|
|
||||||
|
circle = false;
|
||||||
|
square = false;
|
||||||
|
triangle = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Right bumper shoots all balls fastest, ignoring colors
|
||||||
|
if (gamepad2.rightBumperWasPressed()) {
|
||||||
|
shootOrder.clear();
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
|
||||||
|
outtake1 = false;
|
||||||
|
outtake2 = false;
|
||||||
|
outtake3 = false;
|
||||||
|
|
||||||
|
// Fastest order (example: slot 3 → 2 → 1)
|
||||||
|
|
||||||
|
if (ballIn(3)) {
|
||||||
|
shootOrder.add(3);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ballIn(2)) {
|
||||||
|
shootOrder.add(2);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ballIn(1)) {
|
||||||
|
shootOrder.add(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(3)) {
|
||||||
|
|
||||||
|
shootOrder.add(3);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(2)) {
|
||||||
|
|
||||||
|
shootOrder.add(2);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!shootOrder.contains(1)) {
|
||||||
|
|
||||||
|
shootOrder.add(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
shootAll = true;
|
||||||
|
shootPos = drive.localizer.getPose();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// // Right bumper shoots all balls fastest, ignoring colors
|
||||||
|
// if (gamepad2.leftBumperWasPressed()) {
|
||||||
|
// shootOrder.clear();
|
||||||
|
// shootStamp = getRuntime();
|
||||||
|
//
|
||||||
|
// outtake1 = false;
|
||||||
|
// outtake2 = false;
|
||||||
|
// outtake3 = false;
|
||||||
|
//
|
||||||
|
// // Fastest order (example: slot 3 → 2 → 1)
|
||||||
|
//
|
||||||
|
// if (ballIn(3)) {
|
||||||
|
// shootOrder.add(3);
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// if (ballIn(2)) {
|
||||||
|
// shootOrder.add(2);
|
||||||
|
// }
|
||||||
|
// if (ballIn(1)) {
|
||||||
|
// shootOrder.add(1);
|
||||||
|
// }
|
||||||
|
// shootAll = true;
|
||||||
|
// shootPos = drive.localizer.getPose();
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
if (gamepad2.crossWasPressed()) {
|
||||||
|
emergency = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.leftBumperWasPressed()) {
|
||||||
|
emergency = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
//MISC:
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
for (LynxModule hub : allHubs) {
|
||||||
|
hub.clearBulkCache();
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
||||||
|
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
||||||
|
TELE.addData("Spin3Green", green3 + ": " + ballIn(3));
|
||||||
|
|
||||||
|
TELE.addData("pose", drive.localizer.getPose());
|
||||||
|
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
||||||
|
TELE.addData("distanceToGoal", distanceToGoal);
|
||||||
|
TELE.addData("hood", robot.hood.getPosition());
|
||||||
|
TELE.addData("targetVel", vel);
|
||||||
|
|
||||||
|
TELE.addData("shootOrder", shootOrder);
|
||||||
|
TELE.addData("oddColor", oddBallColor);
|
||||||
|
|
||||||
|
aprilTagWebcam.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Helper method
|
||||||
|
private boolean checkGreen(List<Boolean> s, List<Double> sT) {
|
||||||
|
if (s.isEmpty()) return false;
|
||||||
|
|
||||||
|
double lastTime = sT.get(sT.size() - 1);
|
||||||
|
int countTrue = 0;
|
||||||
|
int countWindow = 0;
|
||||||
|
|
||||||
|
for (int i = 0; i < s.size(); i++) {
|
||||||
|
if (lastTime - sT.get(i) <= 3.0) { // element is within 2s of last
|
||||||
|
countWindow++;
|
||||||
|
if (s.get(i)) {
|
||||||
|
countTrue++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (countWindow == 0) return false; // avoid divide by zero
|
||||||
|
return countTrue > countWindow / 2.0; // more than 50% true
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean shootTeleop(double spindexer, boolean spinOk, double stamp) {
|
||||||
|
// Set spin positions
|
||||||
|
spindexPos = spindexer;
|
||||||
|
|
||||||
|
// Check if spindexer has reached the target position
|
||||||
|
if (spinOk || getRuntime() - stamp > 1.5) {
|
||||||
|
if (tickerA == 1) {
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
tickerA++;
|
||||||
|
TELE.addLine("tickerSet");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (getRuntime() - transferStamp > waitTransfer && !transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
transferIn = true;
|
||||||
|
TELE.addLine("transferring");
|
||||||
|
|
||||||
|
return true; // still in progress
|
||||||
|
|
||||||
|
} else if (getRuntime() - transferStamp > waitTransfer + waitTransferOut && transferIn) {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
transferIn = false; // reset for next shot
|
||||||
|
tickerA = 1; // reset ticker
|
||||||
|
transferStamp = 0.0;
|
||||||
|
|
||||||
|
TELE.addLine("shotFinished");
|
||||||
|
|
||||||
|
return false; // finished shooting
|
||||||
|
} else {
|
||||||
|
TELE.addLine("sIP");
|
||||||
|
return true; // still in progress
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
tickerA = 1;
|
||||||
|
transferStamp = getRuntime();
|
||||||
|
transferIn = false;
|
||||||
|
return true; // still moving spin
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public double hoodAnglePrediction(double x) {
|
||||||
|
if (x < 34) {
|
||||||
|
double L = 1.04471;
|
||||||
|
double U = 0.711929;
|
||||||
|
double Q = 120.02263;
|
||||||
|
double B = 0.780982;
|
||||||
|
double M = 20.61191;
|
||||||
|
double v = 10.40506;
|
||||||
|
|
||||||
|
double inner = 1 + Q * Math.exp(-B * (x - M));
|
||||||
|
return L + (U - L) / Math.pow(inner, 1.0 / v);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// x >= 34
|
||||||
|
return 1.94372 * Math.exp(-0.0528731 * x) + 0.39;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddThenRest(List<Integer> order, boolean oddColor) {
|
||||||
|
// Odd ball first
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||||
|
TELE.addData("1", shootOrder);
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||||
|
TELE.addData("works", shootOrder);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddInMiddle(List<Integer> order, boolean oddColor) {
|
||||||
|
|
||||||
|
boolean[] used = new boolean[4]; // index 1..3
|
||||||
|
|
||||||
|
// 1) Add a NON-odd ball first
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (getBallColor(i) != oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 2) Add the odd ball second
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (!used[i] && getBallColor(i) == oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 3) Add the remaining non-odd ball third
|
||||||
|
for (int i = 1; i <= 3; i++) {
|
||||||
|
if (!used[i] && getBallColor(i) != oddColor) {
|
||||||
|
order.add(i);
|
||||||
|
used[i] = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("works", order);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOddLast(List<Integer> order, boolean oddColor) {
|
||||||
|
// Odd ball last
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) != oddColor) order.add(i);
|
||||||
|
TELE.addData("1", shootOrder);
|
||||||
|
for (int i = 1; i <= 3; i++) if (getBallColor(i) == oddColor) order.add(i);
|
||||||
|
TELE.addData("works", shootOrder);
|
||||||
|
TELE.addData("oddBall", oddColor);
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns color of ball in slot i (1-based)
|
||||||
|
boolean getBallColor(int slot) {
|
||||||
|
switch (slot) {
|
||||||
|
case 1:
|
||||||
|
return green1;
|
||||||
|
case 2:
|
||||||
|
return green2;
|
||||||
|
case 3:
|
||||||
|
return green3;
|
||||||
|
}
|
||||||
|
return false; // default
|
||||||
|
}
|
||||||
|
|
||||||
|
boolean ballIn(int slot) {
|
||||||
|
switch (slot) {
|
||||||
|
case 1:
|
||||||
|
|
||||||
|
if (!s1T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s1T.get(s1T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
case 2:
|
||||||
|
|
||||||
|
if (!s2T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s2T.get(s2T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
case 3:
|
||||||
|
|
||||||
|
if (!s3T.isEmpty()) {
|
||||||
|
|
||||||
|
return !(s3T.get(s3T.size() - 1) < (getRuntime()) - 3);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return true; // default
|
||||||
|
}
|
||||||
|
}
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,4 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
public class blank {
|
||||||
|
}
|
||||||
@@ -0,0 +1,793 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.teleop;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Poses.*;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadEx;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
|
||||||
|
import com.arcrobotics.ftclib.gamepad.ToggleButtonReader;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Drivetrain;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Intake;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Spindexer;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Transfer;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@TeleOp
|
||||||
|
@Disabled
|
||||||
|
public class old extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
Drivetrain drivetrain;
|
||||||
|
|
||||||
|
Intake intake;
|
||||||
|
|
||||||
|
Spindexer spindexer;
|
||||||
|
|
||||||
|
Transfer transfer;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
GamepadEx g1;
|
||||||
|
|
||||||
|
GamepadEx g2;
|
||||||
|
|
||||||
|
public static double defaultSpeed = 1;
|
||||||
|
|
||||||
|
public static double slowMoSpeed = 0.4;
|
||||||
|
|
||||||
|
public static double power = 0.0;
|
||||||
|
|
||||||
|
public static double pos = hoodDefault;
|
||||||
|
|
||||||
|
public boolean all = false;
|
||||||
|
|
||||||
|
public int ticker = 0;
|
||||||
|
|
||||||
|
ToggleButtonReader g1RightBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Circle;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Square;
|
||||||
|
|
||||||
|
ToggleButtonReader g2Triangle;
|
||||||
|
|
||||||
|
ToggleButtonReader g2RightBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g1LeftBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2LeftBumper;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadUp;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadDown;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadRight;
|
||||||
|
|
||||||
|
ToggleButtonReader g2DpadLeft;
|
||||||
|
|
||||||
|
public boolean leftBumper = false;
|
||||||
|
public double g1RightBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public double g1LeftBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public double g2LeftBumperStamp = 0.0;
|
||||||
|
|
||||||
|
public static int spindexerPos = 0;
|
||||||
|
|
||||||
|
public boolean green = false;
|
||||||
|
|
||||||
|
Shooter shooter;
|
||||||
|
|
||||||
|
public boolean scoreAll = false;
|
||||||
|
|
||||||
|
MecanumDrive drive;
|
||||||
|
|
||||||
|
public boolean autotrack = false;
|
||||||
|
|
||||||
|
public int last = 0;
|
||||||
|
public int second = 0;
|
||||||
|
|
||||||
|
public double offset = 0.0;
|
||||||
|
|
||||||
|
public static double rIn = 0.59;
|
||||||
|
|
||||||
|
public static double rOut = 0;
|
||||||
|
|
||||||
|
public boolean notShooting = true;
|
||||||
|
|
||||||
|
public boolean circle = false;
|
||||||
|
|
||||||
|
public boolean square = false;
|
||||||
|
|
||||||
|
public boolean tri = false;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(
|
||||||
|
FtcDashboard.getInstance().getTelemetry(),
|
||||||
|
telemetry
|
||||||
|
);
|
||||||
|
|
||||||
|
g1 = new GamepadEx(gamepad1);
|
||||||
|
|
||||||
|
g1RightBumper = new ToggleButtonReader(
|
||||||
|
g1, GamepadKeys.Button.RIGHT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2 = new GamepadEx(gamepad2);
|
||||||
|
|
||||||
|
g1LeftBumper = new ToggleButtonReader(
|
||||||
|
g1, GamepadKeys.Button.LEFT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Circle = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.B
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Triangle = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.Y
|
||||||
|
);
|
||||||
|
|
||||||
|
g2Square = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.X
|
||||||
|
);
|
||||||
|
|
||||||
|
g2RightBumper = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.RIGHT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2LeftBumper = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.LEFT_BUMPER
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadUp = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_UP
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadDown = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_DOWN
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadLeft = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_LEFT
|
||||||
|
);
|
||||||
|
|
||||||
|
g2DpadRight = new ToggleButtonReader(
|
||||||
|
g2, GamepadKeys.Button.DPAD_RIGHT
|
||||||
|
);
|
||||||
|
|
||||||
|
drivetrain = new Drivetrain(robot, TELE, g1);
|
||||||
|
|
||||||
|
drivetrain.setMode("Default");
|
||||||
|
|
||||||
|
drivetrain.setDefaultSpeed(defaultSpeed);
|
||||||
|
|
||||||
|
drivetrain.setSlowSpeed(slowMoSpeed);
|
||||||
|
|
||||||
|
intake = new Intake(robot);
|
||||||
|
|
||||||
|
transfer = new Transfer(robot);
|
||||||
|
|
||||||
|
spindexer = new Spindexer(robot, TELE);
|
||||||
|
|
||||||
|
spindexer.setTelemetryOn(true);
|
||||||
|
|
||||||
|
shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
shooter.setShooterMode("MANUAL");
|
||||||
|
|
||||||
|
robot.rejecter.setPosition(rIn);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
TELE.addData("pose", drive.localizer.getPose());
|
||||||
|
|
||||||
|
TELE.addData("heading", drive.localizer.getPose().heading.toDouble());
|
||||||
|
|
||||||
|
TELE.addData("off", offset);
|
||||||
|
|
||||||
|
robot.hood.setPosition(pos);
|
||||||
|
|
||||||
|
g1LeftBumper.readValue();
|
||||||
|
|
||||||
|
if (g1LeftBumper.wasJustPressed()) {
|
||||||
|
g2LeftBumperStamp = getRuntime();
|
||||||
|
|
||||||
|
spindexer.intakeShake(getRuntime());
|
||||||
|
|
||||||
|
leftBumper = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (leftBumper) {
|
||||||
|
double time = getRuntime() - g2LeftBumperStamp;
|
||||||
|
|
||||||
|
if (time < 1.0) {
|
||||||
|
robot.rejecter.setPosition(rOut);
|
||||||
|
} else {
|
||||||
|
robot.rejecter.setPosition(rIn);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
intake();
|
||||||
|
|
||||||
|
drivetrain.update();
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
transfer.update();
|
||||||
|
|
||||||
|
g2RightBumper.readValue();
|
||||||
|
|
||||||
|
g2LeftBumper.readValue();
|
||||||
|
|
||||||
|
g2DpadDown.readValue();
|
||||||
|
|
||||||
|
g2DpadUp.readValue();
|
||||||
|
|
||||||
|
if (!scoreAll) {
|
||||||
|
spindexer.checkForBalls();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadUp.wasJustPressed()) {
|
||||||
|
pos -= 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadDown.wasJustPressed()) {
|
||||||
|
pos += 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
g2DpadLeft.readValue();
|
||||||
|
|
||||||
|
g2DpadRight.readValue();
|
||||||
|
|
||||||
|
if (g2DpadLeft.wasJustPressed()) {
|
||||||
|
offset -= 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2DpadRight.wasJustPressed()) {
|
||||||
|
offset += 0.02;
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("hood", pos);
|
||||||
|
|
||||||
|
if (Math.abs(gamepad2.right_stick_x) < 0.1 && autotrack) {
|
||||||
|
|
||||||
|
shooter.trackGoal(drive.localizer.getPose(), new Pose2d(-10, 0, 0), offset);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
autotrack = false;
|
||||||
|
|
||||||
|
shooter.moveTurret(0.3 + offset);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.right_stick_button) {
|
||||||
|
autotrack = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2RightBumper.wasJustPressed()) {
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
transfer.transferIn();
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
notShooting = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2RightBumper.wasJustReleased()) {
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
transfer.transferOut();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.left_stick_y > 0.5) {
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
} else if (gamepad2.left_stick_y < -0.5) {
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2LeftBumper.wasJustPressed()) {
|
||||||
|
g2LeftBumperStamp = getRuntime();
|
||||||
|
notShooting = false;
|
||||||
|
scoreAll = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (scoreAll) {
|
||||||
|
double time = getRuntime() - g2LeftBumperStamp;
|
||||||
|
|
||||||
|
shooter.setManualPower(1);
|
||||||
|
|
||||||
|
TELE.addData("greenImportant", green);
|
||||||
|
|
||||||
|
TELE.addData("last", last);
|
||||||
|
TELE.addData("2ndLast", second);
|
||||||
|
|
||||||
|
int numGreen = spindexer.greens();
|
||||||
|
|
||||||
|
if (square) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else if (tri) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else if (circle) {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (numGreen == 2) {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
|
||||||
|
if (time < 0.3) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
last = 0;
|
||||||
|
second = 0;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
} else {
|
||||||
|
all = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
transfer.setTransferPower(1);
|
||||||
|
} else if (time < 2) {
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake3();
|
||||||
|
last = 3;
|
||||||
|
second = 3;
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
second = last;
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 2.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
second = last;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 4) {
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake2();
|
||||||
|
|
||||||
|
last = 2;
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
} else if (time < 4.5) {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
if (gamepad2.right_trigger > 0.5) {
|
||||||
|
green = false;
|
||||||
|
|
||||||
|
all = gamepad2.left_trigger > 0.5;
|
||||||
|
|
||||||
|
} else if (gamepad2.left_trigger > 0.5) {
|
||||||
|
green = true;
|
||||||
|
|
||||||
|
all = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
transfer.transferIn();
|
||||||
|
} else if (time < 6) {
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
if (ticker == 0) {
|
||||||
|
|
||||||
|
if (all) {
|
||||||
|
spindexer.outtake1();
|
||||||
|
} else if (green) {
|
||||||
|
last = spindexer.outtakeGreen(second, last);
|
||||||
|
} else {
|
||||||
|
last = spindexer.outtakePurple(second, last);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
} else if (time < 6.5) {
|
||||||
|
transfer.transferIn();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
ticker = 0;
|
||||||
|
|
||||||
|
scoreAll = false;
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void intake() {
|
||||||
|
|
||||||
|
g1RightBumper.readValue();
|
||||||
|
|
||||||
|
g2Circle.readValue();
|
||||||
|
|
||||||
|
g2Square.readValue();
|
||||||
|
|
||||||
|
g2Triangle.readValue();
|
||||||
|
|
||||||
|
if (g1RightBumper.wasJustPressed()) {
|
||||||
|
|
||||||
|
notShooting = true;
|
||||||
|
|
||||||
|
if (getRuntime() - g1RightBumperStamp < 0.3) {
|
||||||
|
intake.reverse();
|
||||||
|
} else {
|
||||||
|
intake.toggle();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake.getIntakeState() == 1) {
|
||||||
|
shooter.setManualPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
spindexer.intake();
|
||||||
|
|
||||||
|
transfer.transferOut();
|
||||||
|
|
||||||
|
g1RightBumperStamp = getRuntime();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake.getIntakeState() == 1 && notShooting) {
|
||||||
|
|
||||||
|
spindexer.intakeShake(getRuntime());
|
||||||
|
|
||||||
|
} else {
|
||||||
|
if (g2Circle.wasJustPressed()) {
|
||||||
|
circle = true;
|
||||||
|
tri = false;
|
||||||
|
square = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2Triangle.wasJustPressed()) {
|
||||||
|
circle = false;
|
||||||
|
tri = true;
|
||||||
|
square = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (g2Square.wasJustPressed()) {
|
||||||
|
circle = false;
|
||||||
|
tri = false;
|
||||||
|
square = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gamepad2.x) {
|
||||||
|
circle = false;
|
||||||
|
tri = false;
|
||||||
|
square = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
intake.update();
|
||||||
|
|
||||||
|
spindexer.update();
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
@@ -0,0 +1,144 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ActiveColorSensorTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException{
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
int b1Purple = 1;
|
||||||
|
int b1Total = 1;
|
||||||
|
int b2Purple = 1;
|
||||||
|
int b2Total = 1;
|
||||||
|
int b3Purple = 1;
|
||||||
|
int b3Total = 1;
|
||||||
|
|
||||||
|
double totalStamp1 = 0.0;
|
||||||
|
double purpleStamp1 = 0.0;
|
||||||
|
double totalStamp2 = 0.0;
|
||||||
|
double purpleStamp2 = 0.0;
|
||||||
|
double totalStamp3 = 0.0;
|
||||||
|
double purpleStamp3 = 0.0;
|
||||||
|
|
||||||
|
String b1 = "none";
|
||||||
|
String b2 = "none";
|
||||||
|
String b3 = "none";
|
||||||
|
|
||||||
|
double position = 0.0;
|
||||||
|
|
||||||
|
double stamp = getRuntime();
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()){
|
||||||
|
|
||||||
|
if ((getRuntime() % 0.3) >0.15) {
|
||||||
|
position = spindexer_intakePos1 + 0.015;
|
||||||
|
} else {
|
||||||
|
position = spindexer_intakePos1 - 0.015;
|
||||||
|
}
|
||||||
|
robot.spin1.setPosition(position);
|
||||||
|
robot.spin2.setPosition(1-position);
|
||||||
|
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
// Reset the counters after 1 second of not reading a ball.
|
||||||
|
final double ColorCounterResetDelay = 1.0;
|
||||||
|
// Number of times the loop needs to run before deciding on a color.
|
||||||
|
final int ColorCounterTotalMinCount = 20;
|
||||||
|
// If the color sensor reads a color this percentage of time
|
||||||
|
// out of the total, declare the color.
|
||||||
|
// Usage: (Color Count)/(Total Count) > ColorCounterThreshold
|
||||||
|
final double ColorCounterThreshold = 0.65;
|
||||||
|
|
||||||
|
if (robot.pin1.getState()){
|
||||||
|
if (robot.pin0.getState()){
|
||||||
|
b1Purple ++;
|
||||||
|
}
|
||||||
|
b1Total++;
|
||||||
|
totalStamp1 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp1 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b1 = "none";
|
||||||
|
b1Total = 1;
|
||||||
|
b1Purple = 1;
|
||||||
|
}else if ((b1Total > ColorCounterTotalMinCount) && ((double) b1Purple / b1Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b1 = "Purple";
|
||||||
|
}else if (b1Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b1 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
if (robot.pin3.getState()){
|
||||||
|
if (robot.pin2.getState()){
|
||||||
|
b2Purple ++;
|
||||||
|
}
|
||||||
|
b2Total++;
|
||||||
|
totalStamp2 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp2 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b2 = "none";
|
||||||
|
b2Total = 1;
|
||||||
|
b2Purple = 1;
|
||||||
|
}else if ((b2Total > ColorCounterTotalMinCount) && ((double) b2Purple / b2Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b2 = "Purple";
|
||||||
|
}else if (b2Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b2 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
if (robot.pin5.getState()){
|
||||||
|
if (robot.pin4.getState()){
|
||||||
|
b3Purple ++;
|
||||||
|
}
|
||||||
|
b3Total++;
|
||||||
|
totalStamp3 = getRuntime();
|
||||||
|
}
|
||||||
|
if (getRuntime() - totalStamp3 > ColorCounterResetDelay) {
|
||||||
|
// Too Much time has passed without detecting ball
|
||||||
|
b3 = "none";
|
||||||
|
b3Total = 1;
|
||||||
|
b3Purple = 1;
|
||||||
|
}else if ((b3Total > ColorCounterTotalMinCount) && ((double) b3Purple / b3Total) >= ColorCounterThreshold){
|
||||||
|
// Enough Time has passed and we met the threshold
|
||||||
|
b3 = "Purple";
|
||||||
|
}else if (b3Total > ColorCounterTotalMinCount) {
|
||||||
|
// Enough Time passed WITHOUT meeting the threshold
|
||||||
|
b3 = "Green";
|
||||||
|
}
|
||||||
|
|
||||||
|
TELE.addData("Green1:", robot.pin1.getState());
|
||||||
|
TELE.addData("Purple1:", robot.pin0.getState());
|
||||||
|
TELE.addData("Green2:", robot.pin3.getState());
|
||||||
|
TELE.addData("Purple2:", robot.pin2.getState());
|
||||||
|
TELE.addData("Green3:", robot.pin5.getState());
|
||||||
|
TELE.addData("Purple3:", robot.pin4.getState());
|
||||||
|
TELE.addData("1", b1);
|
||||||
|
TELE.addData("2",b2);
|
||||||
|
TELE.addData("3",b3);
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -0,0 +1,63 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ColorSensorTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
// ----- COLOR 1 -----
|
||||||
|
double green1 = robot.color1.getNormalizedColors().green;
|
||||||
|
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||||
|
double red1 = robot.color1.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||||
|
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
// ----- COLOR 2 -----
|
||||||
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
double red2 = robot.color2.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color2 toColor", robot.color2.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color2 green", green2 / (green2 + blue2 + red2));
|
||||||
|
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
// ----- COLOR 3 -----
|
||||||
|
double green3 = robot.color3.getNormalizedColors().green;
|
||||||
|
double blue3 = robot.color3.getNormalizedColors().blue;
|
||||||
|
double red3 = robot.color3.getNormalizedColors().red;
|
||||||
|
|
||||||
|
TELE.addData("Color3 toColor", robot.color3.getNormalizedColors().toColor());
|
||||||
|
TELE.addData("Color3 green", green3 / (green3 + blue3 + red3));
|
||||||
|
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
@@ -1,7 +1,5 @@
|
|||||||
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;
|
||||||
@@ -20,9 +18,6 @@ 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;
|
||||||
@@ -31,34 +26,28 @@ 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)", color1Distance);
|
TELE.addData("Color1 distance (mm)", robot.color1.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
// ----- 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)", color2Distance);
|
TELE.addData("Color2 distance (mm)", robot.color2.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
// ----- 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)", color3Distance);
|
TELE.addData("Color3 distance (mm)", robot.color3.getDistance(DistanceUnit.MM));
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,7 +16,8 @@ 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;
|
||||||
@@ -71,19 +72,19 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
initPos = currentPos;
|
initPos = currentPos;
|
||||||
}
|
}
|
||||||
if (reverse){
|
if (reverse){
|
||||||
robot.spin1.setPosition(manualPow);
|
robot.spin1.setPower(manualPow);
|
||||||
robot.spin2.setPosition(-manualPow);
|
robot.spin2.setPower(-manualPow);
|
||||||
} else {
|
} else {
|
||||||
robot.spin1.setPosition(-manualPow);
|
robot.spin1.setPower(-manualPow);
|
||||||
robot.spin2.setPosition(manualPow);
|
robot.spin2.setPower(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.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
if (getRuntime() - stamp < 1) {
|
if (getRuntime() - stamp < 1) {
|
||||||
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
robot.intake.setPower(-(getRuntime() - stamp)*2);
|
||||||
@@ -190,15 +191,15 @@ public class IntakeTest extends LinearOpMode {
|
|||||||
|
|
||||||
if (!atTarget) {
|
if (!atTarget) {
|
||||||
powPID = servo.setSpinPos(spindexerPos);
|
powPID = servo.setSpinPos(spindexerPos);
|
||||||
robot.spin1.setPosition(powPID);
|
robot.spin1.setPower(powPID);
|
||||||
robot.spin2.setPosition(-powPID);
|
robot.spin2.setPower(-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.setPosition(0);
|
robot.spin1.setPower(0);
|
||||||
robot.spin2.setPosition(0);
|
robot.spin2.setPower(0);
|
||||||
steadySpin = true;
|
steadySpin = true;
|
||||||
wasMoving = false;
|
wasMoving = false;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -4,35 +4,32 @@ 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 org.firstinspires.ftc.teamcode.utils.Robot;
|
import java.util.List;
|
||||||
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;
|
||||||
Turret turret;
|
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
||||||
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());
|
||||||
robot = new Robot(hardwareMap);
|
limelight.pipelineSwitch(pipeline);
|
||||||
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){
|
||||||
robot.limelight.pipelineSwitch(pipeline);
|
limelight.pipelineSwitch(pipeline);
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
LLResult result = limelight.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
TELE.addData("tx", result.getTx());
|
TELE.addData("tx", result.getTx());
|
||||||
@@ -41,29 +38,40 @@ public class LimelightTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else if (mode == 1){
|
} else if (mode == 1){
|
||||||
int obeliskID = turret.detectObelisk();
|
limelight.pipelineSwitch(1);
|
||||||
TELE.addData("Limelight ID", obeliskID);
|
LLResult result = limelight.getLatestResult();
|
||||||
TELE.update();
|
if (result != null && result.isValid()) {
|
||||||
} else if (mode == 2 || mode == 3){ // Use redAlliance variable to switch between red and blue
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
double tx = turret.getBearing();
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
double ty = turret.getTy();
|
int id = fiducial.getFiducialId();
|
||||||
double x = turret.getLimelightX();
|
TELE.addData("ID", id);
|
||||||
double y = turret.getLimelightY();
|
TELE.update();
|
||||||
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.setTurret(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);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -6,9 +6,13 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
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.CRServo;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
|
||||||
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;
|
||||||
@@ -29,7 +33,7 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
|
|
||||||
PIDFController controller = new PIDFController(p, i, d, f);
|
PIDFController controller = new PIDFController(p, i, d, f);
|
||||||
|
|
||||||
controller.setTolerance(0.001);
|
controller.setTolerance(0);
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
@@ -40,16 +44,25 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
controller.setPIDF(p, i, d, f);
|
controller.setPIDF(p, i, d, f);
|
||||||
if (mode == 1) {
|
|
||||||
|
if (mode == 0) {
|
||||||
|
pos = scalar * ((robot.turr1Pos.getVoltage() - restPos) / 3.3);
|
||||||
|
|
||||||
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
|
robot.turr1.setPower(pid);
|
||||||
|
robot.turr2.setPower(-pid);
|
||||||
|
} else if (mode == 1) {
|
||||||
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
pos = scalar * ((robot.spin1Pos.getVoltage() - restPos) / 3.3);
|
||||||
|
|
||||||
double pid = controller.calculate(pos, target);
|
double pid = controller.calculate(pos, target);
|
||||||
|
|
||||||
robot.spin1.setPosition(pid);
|
robot.spin1.setPower(pid);
|
||||||
robot.spin2.setPosition(-pid);
|
robot.spin2.setPower(-pid);
|
||||||
}
|
}
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
telemetry.addData("pos", pos);
|
||||||
|
telemetry.addData("Turret Voltage", robot.turr1Pos.getVoltage());
|
||||||
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);
|
||||||
@@ -58,5 +71,4 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -1,66 +1,32 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_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_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 static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
|
|
||||||
|
|
||||||
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;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
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.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
|
||||||
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.Spindexer;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@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 ---
|
||||||
|
|
||||||
public static double Velocity = 0.0;
|
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||||
public static double P = 255.0;
|
|
||||||
public static double I = 0.0;
|
|
||||||
public static double D = 0.0;
|
|
||||||
public static double F = 90;
|
|
||||||
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;
|
|
||||||
public static boolean turretTrack = true;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
Servos servo;
|
|
||||||
MecanumDrive drive;
|
|
||||||
Turret turret;
|
|
||||||
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;
|
|
||||||
public static double spinSpeed = 0.02;
|
|
||||||
Spindexer spindexer ;
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -68,136 +34,47 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
DcMotorEx leftShooter = robot.shooter1;
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new Flywheel();
|
||||||
spindexer = new Spindexer(hardwareMap);
|
|
||||||
servo = new Servos(hardwareMap);
|
|
||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0,0,0));
|
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
);
|
);
|
||||||
turret = new Turret(robot, TELE, robot.limelight);
|
|
||||||
Turret.limelightUsed = true;
|
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
robot.limelight.start();
|
|
||||||
|
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
if (redAlliance){
|
|
||||||
robot.limelight.pipelineSwitch(4);
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
//TURRET TRACKING
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
|
||||||
double goalY = 0;
|
|
||||||
|
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
|
||||||
double dy = robY - goalY; // delta y from robot to goal
|
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
if (turretTrack){
|
|
||||||
turret.trackGoal(deltaPose);
|
|
||||||
} else if (turretPos != 0.501){
|
|
||||||
turret.setTurret(turretPos);
|
|
||||||
}
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
|
||||||
|
|
||||||
if (mode == 0) {
|
if (mode == 0) {
|
||||||
rightShooter.setPower(parameter);
|
rightShooter.setPower(parameter);
|
||||||
leftShooter.setPower(parameter);
|
leftShooter.setPower(parameter);
|
||||||
} else if (mode == 1) {
|
} else if (mode == 1) {
|
||||||
flywheel.setPIDF(P, I, D, F / voltage);
|
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition());
|
||||||
flywheel.manageFlywheel((int) Velocity);
|
rightShooter.setPower(powPID);
|
||||||
|
leftShooter.setPower(powPID);
|
||||||
|
TELE.addData("PIDPower", powPID);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
if (enableHoodAutoOpen) {
|
robot.hood.setPosition(hoodPos);
|
||||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
|
||||||
} else {
|
|
||||||
robot.hood.setPosition(hoodPos);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (intake) {
|
if (turretPos != 0.501) {
|
||||||
robot.intake.setPower(1);
|
robot.turr1.setPower(turretPos);
|
||||||
|
robot.turr2.setPower(turretPos);
|
||||||
} else {
|
|
||||||
robot.intake.setPower(0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
robot.transfer.setPower(transferPower);
|
||||||
if (shoot) {
|
if (shoot) {
|
||||||
shootStamp = getRuntime();
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
shootAll = true;
|
|
||||||
shoot = false;
|
|
||||||
robot.transfer.setPower(transferPower);
|
|
||||||
shooterTicker = 0;
|
|
||||||
}
|
|
||||||
if (shootAll) {
|
|
||||||
|
|
||||||
//intake = false;
|
|
||||||
//reject = false;
|
|
||||||
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
|
||||||
if (getRuntime() - shootStamp < 3.5) {
|
|
||||||
|
|
||||||
if (shooterTicker == 0 && !servo.spinEqual(spinStartPos)){
|
|
||||||
robot.spin1.setPosition(spinStartPos);
|
|
||||||
robot.spin2.setPosition(1-spinStartPos);
|
|
||||||
} else {
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
|
||||||
shooterTicker++;
|
|
||||||
double prevSpinPos = robot.spin1.getPosition();
|
|
||||||
|
|
||||||
if (prevSpinPos < 0.9){
|
|
||||||
robot.spin1.setPosition(prevSpinPos + spinSpeed);
|
|
||||||
robot.spin2.setPosition(1 - prevSpinPos - spinSpeed);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
} else {
|
|
||||||
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 {
|
} else {
|
||||||
spindexer.processIntake();
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
TELE.addData("Velocity", flywheel.getVelo());
|
||||||
TELE.addData("Velocity 1", flywheel.getVelo1());
|
|
||||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
|
||||||
TELE.addData("Power", robot.shooter1.getPower());
|
TELE.addData("Power", robot.shooter1.getPower());
|
||||||
TELE.addData("Steady?", flywheel.getSteady());
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
TELE.addData("Position", robot.shooter1.getCurrentPosition());
|
TELE.addData("Position", robot.shooter1.getCurrentPosition());
|
||||||
TELE.addData("Voltage", voltage);
|
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
|
|||||||
@@ -1,51 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
|
||||||
|
|
||||||
@TeleOp
|
|
||||||
@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();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,210 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
|
||||||
|
|
||||||
|
@TeleOp
|
||||||
|
@Config
|
||||||
|
public class ShooterTest extends LinearOpMode {
|
||||||
|
|
||||||
|
Robot robot;
|
||||||
|
|
||||||
|
public static double pow = 0.0;
|
||||||
|
public static double vel = 0.0;
|
||||||
|
public static double ecpr = 1024.0; // CPR of the encoder
|
||||||
|
public static double hoodPos = 0.5;
|
||||||
|
public static double turretPos = 0.9;
|
||||||
|
|
||||||
|
public static String flyMode = "VEL";
|
||||||
|
|
||||||
|
public static boolean AutoTrack = false;
|
||||||
|
|
||||||
|
double initPos = 0.0;
|
||||||
|
|
||||||
|
double velo = 0.0;
|
||||||
|
double velo1 = 0.0;
|
||||||
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
|
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
|
||||||
|
double initPos1 = 0.0;
|
||||||
|
|
||||||
|
double powPID = 0.0;
|
||||||
|
|
||||||
|
public static int maxVel = 4500;
|
||||||
|
|
||||||
|
public static boolean shoot = false;
|
||||||
|
|
||||||
|
public static int spindexPos = 1;
|
||||||
|
|
||||||
|
public static boolean intake = true;
|
||||||
|
|
||||||
|
public static int tolerance = 50;
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
public static double distance = 50;
|
||||||
|
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
Shooter shooter = new Shooter(robot, TELE);
|
||||||
|
|
||||||
|
robot.shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
robot.shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
shooter.setTelemetryOn(true);
|
||||||
|
|
||||||
|
shooter.setShooterMode(flyMode);
|
||||||
|
|
||||||
|
initPos = shooter.getECPRPosition();
|
||||||
|
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
if (AutoTrack){
|
||||||
|
hoodPos = hoodAnglePrediction(distance);
|
||||||
|
vel = velPrediction(distance);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
shooter.setShooterMode(flyMode);
|
||||||
|
|
||||||
|
shooter.setManualPower(pow);
|
||||||
|
|
||||||
|
robot.hood.setPosition(hoodPos);
|
||||||
|
robot.turr1.setPosition(turretPos);
|
||||||
|
robot.turr2.setPosition(1 - turretPos);
|
||||||
|
if (intake) {
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
robot.intake.setPower(0.75);
|
||||||
|
robot.spin1.setPosition(spindexer_intakePos1);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_intakePos1);
|
||||||
|
} else {
|
||||||
|
robot.transfer.setPower(.75 + (powPID/4));
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
if (spindexPos == 1) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall1);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall1);
|
||||||
|
} else if (spindexPos == 2) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall2);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall2);
|
||||||
|
} else if (spindexPos == 3) {
|
||||||
|
robot.spin1.setPosition(spindexer_outtakeBall3);
|
||||||
|
robot.spin2.setPosition(1 - spindexer_outtakeBall3);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
double penguin = 0;
|
||||||
|
if (ticker % 8 ==0){
|
||||||
|
penguin = shooter.getECPRPosition();
|
||||||
|
stamp = getRuntime();
|
||||||
|
velo1 = -60 * ((penguin - initPos1) / (stamp - stamp1));
|
||||||
|
initPos1 = penguin;
|
||||||
|
stamp1 = stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
velo = velo1;
|
||||||
|
|
||||||
|
double feed = vel / maxVel; // Example: vel=2500 → feed=0.5
|
||||||
|
|
||||||
|
if (vel > 500){
|
||||||
|
feed = Math.log((668.39 / (vel + 591.96)) - 0.116) / -4.18;
|
||||||
|
}
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = vel - velo1;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
|
||||||
|
if (vel - velo > 1000){
|
||||||
|
powPID = 1;
|
||||||
|
} else if (velo - vel > 1000){
|
||||||
|
powPID = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.setVelocity(powPID);
|
||||||
|
|
||||||
|
if (shoot) {
|
||||||
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
} else {
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
}
|
||||||
|
|
||||||
|
shooter.update();
|
||||||
|
|
||||||
|
TELE.addData("Revolutions", shooter.getECPRPosition());
|
||||||
|
TELE.addData("hoodPos", shooter.gethoodPosition());
|
||||||
|
TELE.addData("turretPos", shooter.getTurretPosition());
|
||||||
|
TELE.addData("Power Fly 1", robot.shooter1.getPower());
|
||||||
|
TELE.addData("Power Fly 2", robot.shooter2.getPower());
|
||||||
|
TELE.addData("powPID", shooter.getpowPID());
|
||||||
|
TELE.addData("Velocity", velo);
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public double hoodAnglePrediction(double distance) {
|
||||||
|
double L = 0.298317;
|
||||||
|
double A = 1.02124;
|
||||||
|
double k = 0.0157892;
|
||||||
|
double n = 3.39375;
|
||||||
|
|
||||||
|
double dist = Math.sqrt(distance*distance+24*24);
|
||||||
|
|
||||||
|
return L + A * Math.exp(-Math.pow(k * dist, n));
|
||||||
|
}
|
||||||
|
public static double velPrediction(double distance) {
|
||||||
|
|
||||||
|
double x = Math.sqrt(distance*distance+24*24);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
double A = -211149.992;
|
||||||
|
double B = -1.19943;
|
||||||
|
double C = 3720.15909;
|
||||||
|
|
||||||
|
return A * Math.pow(x, B) + C;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
@@ -1,87 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
|
||||||
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
|
||||||
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.hardware.DcMotor;
|
|
||||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
|
|
||||||
public class Drivetrain {
|
|
||||||
|
|
||||||
Robot robot;
|
|
||||||
boolean autoDrive = false;
|
|
||||||
|
|
||||||
Pose2d brakePos = new Pose2d(0, 0, 0);
|
|
||||||
|
|
||||||
MecanumDrive drive;
|
|
||||||
|
|
||||||
private final TranslationalVelConstraint VEL_CONSTRAINT = new TranslationalVelConstraint(200);
|
|
||||||
private final ProfileAccelConstraint ACCEL_CONSTRAINT = new ProfileAccelConstraint(-Math.abs(60), 200);
|
|
||||||
|
|
||||||
|
|
||||||
public Drivetrain (Robot rob, MecanumDrive mecanumDrive){
|
|
||||||
|
|
||||||
this.robot = rob;
|
|
||||||
this.drive = mecanumDrive;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public void drive(double y, double x, double rx, double brake){
|
|
||||||
|
|
||||||
if (!autoDrive) {
|
|
||||||
|
|
||||||
x = x* 1.1; // Counteract imperfect strafing
|
|
||||||
|
|
||||||
|
|
||||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
|
||||||
double frontLeftPower = (y + x + rx) / denominator;
|
|
||||||
double backLeftPower = (y - x + rx) / denominator;
|
|
||||||
double frontRightPower = (y - x - rx) / denominator;
|
|
||||||
double backRightPower = (y + x - rx) / denominator;
|
|
||||||
|
|
||||||
robot.frontLeft.setPower(frontLeftPower);
|
|
||||||
robot.backLeft.setPower(backLeftPower);
|
|
||||||
robot.frontRight.setPower(frontRightPower);
|
|
||||||
robot.backRight.setPower(backRightPower);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (brake > 0.4 && robot.frontLeft.getZeroPowerBehavior() != DcMotor.ZeroPowerBehavior.BRAKE && !autoDrive) {
|
|
||||||
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
brakePos = drive.localizer.getPose();
|
|
||||||
autoDrive = true;
|
|
||||||
|
|
||||||
} else if (brake > 0.4) {
|
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
Pose2d currentPos = drive.localizer.getPose();
|
|
||||||
|
|
||||||
TrajectoryActionBuilder traj2 = drive.actionBuilder(currentPos)
|
|
||||||
.strafeToLinearHeading(new Vector2d(brakePos.position.x, brakePos.position.y), brakePos.heading.toDouble(), VEL_CONSTRAINT, ACCEL_CONSTRAINT);
|
|
||||||
|
|
||||||
if (Math.abs(currentPos.position.x - brakePos.position.x) > 1 || Math.abs(currentPos.position.y - brakePos.position.y) > 1) {
|
|
||||||
Actions.runBlocking(
|
|
||||||
traj2.build()
|
|
||||||
);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
autoDrive = false;
|
|
||||||
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
|
||||||
robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
|
||||||
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
|
||||||
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,84 +1,88 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
|
||||||
public class Flywheel {
|
public class Flywheel {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
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;
|
||||||
public double velo1 = 0.0;
|
double velo1 = 0.0;
|
||||||
public double velo2 = 0.0;
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double previousTargetVelocity = 0.0;
|
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public Flywheel (HardwareMap hardwareMap) {
|
public Flywheel () {
|
||||||
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 () {
|
||||||
return velo;
|
return velo;
|
||||||
}
|
}
|
||||||
public double getVelo1 () {
|
|
||||||
return velo1;
|
|
||||||
}
|
|
||||||
public double getVelo2 () {
|
|
||||||
return velo2;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean getSteady() {
|
public boolean getSteady() {
|
||||||
return steady;
|
return steady;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the robot PIDF for the next cycle.
|
private double getTimeSeconds ()
|
||||||
private double prevF = 0.501;
|
{
|
||||||
public static int voltagePIDFDifference = 5;
|
return (double) System.currentTimeMillis()/1000.0;
|
||||||
public void setPIDF(double p, double i, double d, double f) {
|
|
||||||
shooterPIDF1.p = p;
|
|
||||||
shooterPIDF1.i = i;
|
|
||||||
shooterPIDF1.d = d;
|
|
||||||
shooterPIDF1.f = f;
|
|
||||||
shooterPIDF2.p = p;
|
|
||||||
shooterPIDF2.i = i;
|
|
||||||
shooterPIDF2.d = d;
|
|
||||||
shooterPIDF2.f = f;
|
|
||||||
if (Math.abs(prevF - f) > voltagePIDFDifference){
|
|
||||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
|
||||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert from RPM to Ticks per Second
|
|
||||||
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
|
||||||
|
|
||||||
// Convert from Ticks per Second to RPM
|
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
||||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
targetVelocity = commandedVelocity;
|
||||||
|
|
||||||
public double manageFlywheel(double commandedVelocity) {
|
ticker++;
|
||||||
|
if (ticker % 2 == 0) {
|
||||||
|
velo5 = velo4;
|
||||||
|
velo4 = velo3;
|
||||||
|
velo3 = velo2;
|
||||||
|
velo2 = velo1;
|
||||||
|
|
||||||
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
|
currentPos = shooter1CurPos / 2048;
|
||||||
targetVelocity = commandedVelocity;
|
stamp = getTimeSeconds(); //getRuntime();
|
||||||
// Add code here to set PIDF based on desired RPM
|
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
||||||
//robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
initPos = currentPos;
|
||||||
//robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
stamp1 = stamp;
|
||||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
|
||||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
|
||||||
|
|
||||||
// Record Current Velocity
|
|
||||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
|
||||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
|
||||||
velo = Math.max(velo1, velo2);
|
|
||||||
|
|
||||||
|
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
||||||
}
|
}
|
||||||
|
// Flywheel control code here
|
||||||
|
if (targetVelocity - velo > 500) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - targetVelocity > 500){
|
||||||
|
powPID = 0.0;
|
||||||
|
} else {
|
||||||
|
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = targetVelocity - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
// really should be a running average of the last 5
|
// really should be a running average of the last 5
|
||||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||||
|
|
||||||
return powPID;
|
return powPID;
|
||||||
}
|
}
|
||||||
@@ -86,4 +90,4 @@ public class Flywheel {
|
|||||||
public void update()
|
public void update()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -0,0 +1,104 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class FlywheelV2 {
|
||||||
|
public static double kP = 0.001; // small proportional gain (tune this)
|
||||||
|
public static double maxStep = 0.06; // prevents sudden jumps
|
||||||
|
double initPos1 = 0.0;
|
||||||
|
double initPos2 = 0.0;
|
||||||
|
double stamp = 0.0;
|
||||||
|
double stamp1 = 0.0;
|
||||||
|
double ticker = 0.0;
|
||||||
|
double currentPos1 = 0.0;
|
||||||
|
double currentPos2 = 0.0;
|
||||||
|
double velo = 0.0;
|
||||||
|
double velo1 = 0.0;
|
||||||
|
double velo1a = 0.0;
|
||||||
|
double velo1b = 0.0;
|
||||||
|
double velo2 = 0.0;
|
||||||
|
double velo3 = 0.0;
|
||||||
|
double velo4 = 0.0;
|
||||||
|
double velo5 = 0.0;
|
||||||
|
double targetVelocity = 0.0;
|
||||||
|
double powPID = 0.0;
|
||||||
|
boolean steady = false;
|
||||||
|
|
||||||
|
public FlywheelV2() {
|
||||||
|
//robot = new Robot(hardwareMap);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getVelo(double shooter1CurPos, double shooter2CurPos) {
|
||||||
|
ticker++;
|
||||||
|
if (ticker % 2 == 0) {
|
||||||
|
velo5 = velo4;
|
||||||
|
velo4 = velo3;
|
||||||
|
velo3 = velo2;
|
||||||
|
velo2 = velo1;
|
||||||
|
|
||||||
|
currentPos1 = shooter1CurPos / 28;
|
||||||
|
currentPos2 = shooter2CurPos / 28;
|
||||||
|
stamp = getTimeSeconds(); //getRuntime();
|
||||||
|
velo1a = 60 * ((currentPos1 - initPos1) / (stamp - stamp1));
|
||||||
|
velo1b = 60 * ((currentPos2 - initPos2) / (stamp - stamp1));
|
||||||
|
initPos1 = currentPos1;
|
||||||
|
initPos2 = currentPos2;
|
||||||
|
stamp1 = stamp;
|
||||||
|
|
||||||
|
if (velo1a < 200){
|
||||||
|
velo1 = velo1b;
|
||||||
|
} else if (velo1b < 200){
|
||||||
|
velo1 = velo1a;
|
||||||
|
} else {
|
||||||
|
velo1 = (velo1a + velo1b) / 2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return ((velo1 + velo2 + velo3 + velo4 + velo5) / 5);
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getVelo1() { return (velo1a + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||||
|
|
||||||
|
public double getVelo2() { return (velo1b + velo2 + velo3 + velo4 + velo5) / 5; }
|
||||||
|
|
||||||
|
public boolean getSteady() {
|
||||||
|
return steady;
|
||||||
|
}
|
||||||
|
|
||||||
|
private double getTimeSeconds() {
|
||||||
|
return (double) System.currentTimeMillis() / 1000.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double manageFlywheel(int commandedVelocity, double shooter1CurPos, double shooter2CurPos) {
|
||||||
|
targetVelocity = commandedVelocity;
|
||||||
|
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
||||||
|
// Flywheel PID code here
|
||||||
|
if (targetVelocity - velo > 500) {
|
||||||
|
powPID = 1.0;
|
||||||
|
} else if (velo - targetVelocity > 500) {
|
||||||
|
powPID = 0.0;
|
||||||
|
} else {
|
||||||
|
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||||
|
|
||||||
|
// --- PROPORTIONAL CORRECTION ---
|
||||||
|
double error = targetVelocity - velo;
|
||||||
|
double correction = kP * error;
|
||||||
|
|
||||||
|
// limit how fast power changes (prevents oscillation)
|
||||||
|
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||||
|
|
||||||
|
// --- FINAL MOTOR POWER ---
|
||||||
|
powPID = feed + correction;
|
||||||
|
|
||||||
|
// clamp to allowed range
|
||||||
|
powPID = Math.max(0, Math.min(1, powPID));
|
||||||
|
}
|
||||||
|
|
||||||
|
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
||||||
|
|
||||||
|
return powPID;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,108 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.StateEnums.LightState;
|
|
||||||
|
|
||||||
|
|
||||||
@Config
|
|
||||||
public final class Light {
|
|
||||||
|
|
||||||
private static Light instance;
|
|
||||||
public static double ballColorCycleTime = 1000; //in ms
|
|
||||||
public static double restingTime = 150; //in ms
|
|
||||||
|
|
||||||
private Servo lightServo;
|
|
||||||
private LightState state = LightState.DISABLED;
|
|
||||||
|
|
||||||
// References to other systems (NOT static)
|
|
||||||
private Spindexer spindexer;
|
|
||||||
private Turret turret;
|
|
||||||
private double manualLightColor = Color.Light0;
|
|
||||||
|
|
||||||
private double lightColor = Color.Light0;
|
|
||||||
private double previousLightColor = lightColor;
|
|
||||||
|
|
||||||
private Light() {
|
|
||||||
}
|
|
||||||
|
|
||||||
public static synchronized Light getInstance() {
|
|
||||||
if (instance == null) {
|
|
||||||
instance = new Light();
|
|
||||||
}
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Call once in OpMode init()
|
|
||||||
public void init(
|
|
||||||
Servo servo,
|
|
||||||
Spindexer spin,
|
|
||||||
Turret turr
|
|
||||||
) {
|
|
||||||
this.lightServo = servo;
|
|
||||||
this.spindexer = spin;
|
|
||||||
this.turret = turr;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setManualLightColor(double value) {
|
|
||||||
this.manualLightColor = value;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setState(LightState newState) {
|
|
||||||
state = newState;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void update() {
|
|
||||||
if (lightServo == null) return;
|
|
||||||
|
|
||||||
switch (state) {
|
|
||||||
|
|
||||||
case BALL_COUNT:
|
|
||||||
lightColor = spindexer.ballCounterLight();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case BALL_COLOR:
|
|
||||||
|
|
||||||
if ((System.currentTimeMillis() % ballColorCycleTime) < ((ballColorCycleTime / 3) - restingTime)) {
|
|
||||||
lightColor = spindexer.getRearCenterLight();
|
|
||||||
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime / 3)) {
|
|
||||||
lightColor = 0;
|
|
||||||
} else if ((System.currentTimeMillis() % ballColorCycleTime) < ((2 * ballColorCycleTime / 3) - restingTime)) {
|
|
||||||
lightColor = spindexer.getDriverLight();
|
|
||||||
|
|
||||||
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (2 * ballColorCycleTime / 3)) {
|
|
||||||
lightColor = 0;
|
|
||||||
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime - restingTime)) {
|
|
||||||
lightColor = spindexer.getPassengerLight();
|
|
||||||
|
|
||||||
} else {
|
|
||||||
lightColor = 0;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case GOAL_LOCK:
|
|
||||||
lightColor = turret.getLightColor();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MANUAL:
|
|
||||||
lightColor = manualLightColor;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case DISABLED:
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OFF:
|
|
||||||
lightColor = 0;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (lightColor != previousLightColor) {
|
|
||||||
lightServo.setPosition(lightColor);
|
|
||||||
}
|
|
||||||
|
|
||||||
previousLightColor = lightColor;
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -0,0 +1,103 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class LimelightManager {
|
||||||
|
private Limelight3A limelight;
|
||||||
|
private LLResult lastResult;
|
||||||
|
private int lastFiducialId = -1;
|
||||||
|
private double lastBearing = 0.0;
|
||||||
|
|
||||||
|
public static final int PIPELINE_DEFAULT = 1;
|
||||||
|
public static final int PIPELINE_BLUE_DETECTION = 2;
|
||||||
|
public static final int PIPELINE_RED_DETECTION = 3;
|
||||||
|
|
||||||
|
public enum LimelightMode {
|
||||||
|
OBELISK_DETECTION(PIPELINE_DEFAULT),
|
||||||
|
BLUE_GOAL(PIPELINE_BLUE_DETECTION),
|
||||||
|
RED_GOAL(PIPELINE_RED_DETECTION);
|
||||||
|
|
||||||
|
public final int pipeline;
|
||||||
|
|
||||||
|
LimelightMode(int pipeline) {
|
||||||
|
this.pipeline = pipeline;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public LimelightManager(HardwareMap hardwareMap, boolean enabled) {
|
||||||
|
if (enabled) {
|
||||||
|
this.limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void init() {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.start();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void switchMode(LimelightMode mode) {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.pipelineSwitch(mode.pipeline);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setPipeline(int pipeline) {
|
||||||
|
if (limelight != null) {
|
||||||
|
limelight.pipelineSwitch(pipeline);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
if (limelight != null) {
|
||||||
|
lastResult = limelight.getLatestResult();
|
||||||
|
if (lastResult != null && lastResult.isValid()) {
|
||||||
|
lastBearing = lastResult.getTx();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getBearing() {
|
||||||
|
return lastBearing;
|
||||||
|
}
|
||||||
|
|
||||||
|
public int detectFiducial() {
|
||||||
|
if (lastResult != null && lastResult.isValid()) {
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = lastResult.getFiducialResults();
|
||||||
|
if (!fiducials.isEmpty()) {
|
||||||
|
lastFiducialId = fiducials.get(0).getFiducialId();
|
||||||
|
return lastFiducialId;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
public int getLastFiducialId() {
|
||||||
|
return lastFiducialId;
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isFiducialDetected(int id) {
|
||||||
|
return lastFiducialId == id;
|
||||||
|
}
|
||||||
|
|
||||||
|
public LLResult getLatestResult() {
|
||||||
|
return lastResult;
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isConnected() {
|
||||||
|
return limelight != null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public Limelight3A getLimelight() {
|
||||||
|
return limelight;
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,66 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
|
||||||
|
|
||||||
public class MeasuringLoopTimes {
|
|
||||||
private ElapsedTime elapsedtime;
|
|
||||||
private double minLoopTime = 999999999999.0;
|
|
||||||
|
|
||||||
private double maxLoopTime = 0.0;
|
|
||||||
private double mainLoopTime = 0.0;
|
|
||||||
|
|
||||||
private double MeasurementStart = 0.0;
|
|
||||||
private double currentTime = 0.0;
|
|
||||||
|
|
||||||
private double avgLoopTime = 0.0;
|
|
||||||
private int avgLoopTimeTicker = 0;
|
|
||||||
private double avgLoopTimeSum = 0;
|
|
||||||
|
|
||||||
private double getTimeSeconds ()
|
|
||||||
{
|
|
||||||
return (double) System.currentTimeMillis()/1000.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void init() {
|
|
||||||
elapsedtime = new ElapsedTime();
|
|
||||||
elapsedtime.reset();
|
|
||||||
|
|
||||||
MeasurementStart = getTimeSeconds();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
public double getAvgLoopTime() {
|
|
||||||
return avgLoopTime;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getMaxLoopTimeOneMin() {
|
|
||||||
return maxLoopTime;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getMinLoopTimeOneMin() {
|
|
||||||
return minLoopTime;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void loop() {
|
|
||||||
currentTime = getTimeSeconds();
|
|
||||||
if ((MeasurementStart + 15.0) < currentTime)
|
|
||||||
{
|
|
||||||
minLoopTime = 9999999.0;
|
|
||||||
maxLoopTime = 0.0;
|
|
||||||
MeasurementStart = currentTime;
|
|
||||||
|
|
||||||
avgLoopTime = avgLoopTimeSum / (double) avgLoopTimeTicker;
|
|
||||||
avgLoopTimeSum = 0.0;
|
|
||||||
avgLoopTimeTicker = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
mainLoopTime = elapsedtime.milliseconds();
|
|
||||||
elapsedtime.reset();
|
|
||||||
|
|
||||||
avgLoopTimeSum += mainLoopTime;
|
|
||||||
avgLoopTimeTicker++;
|
|
||||||
minLoopTime = Math.min(minLoopTime,mainLoopTime);
|
|
||||||
maxLoopTime = Math.max(maxLoopTime,mainLoopTime);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -8,8 +8,6 @@ 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 {
|
||||||
@@ -18,30 +16,44 @@ 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 double light = 0.501;
|
public static int mode = 0; //0 for positional, 1 for power
|
||||||
|
|
||||||
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){
|
if (spindexPos != 0.501 && !servo.spinEqual(spindexPos) && mode == 0){
|
||||||
robot.spin1.setPosition(spindexPos);
|
double pos = servo.setSpinPos(spindexPos);
|
||||||
robot.spin2.setPosition(1-spindexPos);
|
robot.spin1.setPower(pos);
|
||||||
|
robot.spin2.setPower(-pos);
|
||||||
|
} else if (mode == 0){
|
||||||
|
robot.spin1.setPower(spinHoldPow);
|
||||||
|
robot.spin2.setPower(spinHoldPow);
|
||||||
|
} else {
|
||||||
|
robot.spin1.setPower(spindexPow);
|
||||||
|
robot.spin2.setPower(-spindexPow);
|
||||||
}
|
}
|
||||||
if (turretPos != 0.501){
|
if (turretPos != 0.501 && !servo.turretEqual(turretPos)){
|
||||||
robot.turr1.setPosition(turretPos);
|
double pos = servo.setTurrPos(turretPos);
|
||||||
robot.turr2.setPosition(1-turretPos);
|
robot.turr1.setPower(pos);
|
||||||
|
robot.turr2.setPower(-pos);
|
||||||
|
} else if (mode == 0){
|
||||||
|
robot.turr1.setPower(turrHoldPow);
|
||||||
|
robot.turr2.setPower(turrHoldPow);
|
||||||
|
} else {
|
||||||
|
robot.turr1.setPower(turretPow);
|
||||||
|
robot.turr2.setPower(-turretPow);
|
||||||
}
|
}
|
||||||
if (transferPos != 0.501){
|
if (transferPos != 0.501){
|
||||||
robot.transferServo.setPosition(transferPos);
|
robot.transferServo.setPosition(transferPos);
|
||||||
@@ -49,17 +61,13 @@ 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){
|
TELE.addData("spindexer", servo.getSpinPos());
|
||||||
robot.light.setPosition(light);
|
TELE.addData("turret", servo.getTurrPos());
|
||||||
}
|
TELE.addData("spindexer voltage", robot.spin1Pos.getVoltage());
|
||||||
|
TELE.addData("hood voltage", robot.hoodPos.getVoltage());
|
||||||
TELE.addData("spindexer pos", servo.getSpinPos());
|
|
||||||
TELE.addData("turret pos", robot.turr1.getPosition());
|
|
||||||
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
|
||||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
|
||||||
TELE.addData("hood pos", robot.hood.getPosition());
|
|
||||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||||
TELE.addData("tpos ", turret.getTurrPos() );
|
TELE.addData("turret voltage", robot.turr1Pos.getVoltage());
|
||||||
|
TELE.addData("Spin Equal", servo.spinEqual(spindexPos));
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,7 +1,5 @@
|
|||||||
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;
|
||||||
@@ -9,59 +7,60 @@ import com.qualcomm.robotcore.hardware.CRServo;
|
|||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
import com.qualcomm.robotcore.hardware.VoltageSensor;
|
|
||||||
|
|
||||||
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;
|
||||||
public DcMotorEx backRight;
|
public DcMotorEx backRight;
|
||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
public DcMotorEx transfer;
|
public DcMotorEx transfer;
|
||||||
public PIDFCoefficients shooterPIDF;
|
|
||||||
public double shooterPIDF_P = 255.0;
|
|
||||||
public double shooterPIDF_I = 0.0;
|
|
||||||
public double shooterPIDF_D = 0.0;
|
|
||||||
public double shooterPIDF_F = 90;
|
|
||||||
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 rejecter;
|
||||||
public Servo turr2;
|
public CRServo turr1;
|
||||||
|
public CRServo turr2;
|
||||||
public Servo spin1;
|
public CRServo spin1;
|
||||||
|
public CRServo spin2;
|
||||||
public Servo spin2;
|
public DigitalChannel pin0;
|
||||||
|
public DigitalChannel pin1;
|
||||||
|
public DigitalChannel pin2;
|
||||||
|
public DigitalChannel pin3;
|
||||||
|
public DigitalChannel pin4;
|
||||||
|
public DigitalChannel pin5;
|
||||||
|
public AnalogInput analogInput;
|
||||||
|
public AnalogInput analogInput2;
|
||||||
public AnalogInput spin1Pos;
|
public AnalogInput spin1Pos;
|
||||||
public AnalogInput spin2Pos;
|
public AnalogInput spin2Pos;
|
||||||
|
public AnalogInput hoodPos;
|
||||||
public AnalogInput turr1Pos;
|
public AnalogInput turr1Pos;
|
||||||
|
public AnalogInput turr2Pos;
|
||||||
public AnalogInput transferServoPos;
|
public AnalogInput transferServoPos;
|
||||||
public AprilTagProcessor aprilTagProcessor;
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
public WebcamName webcam;
|
public WebcamName webcam;
|
||||||
|
public DcMotorEx shooterEncoder;
|
||||||
public RevColorSensorV3 color1;
|
public RevColorSensorV3 color1;
|
||||||
public RevColorSensorV3 color2;
|
public RevColorSensorV3 color2;
|
||||||
public RevColorSensorV3 color3;
|
public RevColorSensorV3 color3;
|
||||||
public Limelight3A limelight;
|
public Limelight3A limelight;
|
||||||
public Servo light;
|
|
||||||
public VoltageSensor voltage;
|
public static boolean usingLimelight = true;
|
||||||
|
|
||||||
public Robot(HardwareMap hardwareMap) {
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
//Define components w/ hardware map
|
//Define components w/ hardware map
|
||||||
|
|
||||||
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
|
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
|
||||||
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
|
||||||
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
|
||||||
@@ -75,36 +74,57 @@ public class Robot {
|
|||||||
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
|
||||||
|
|
||||||
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
intake = hardwareMap.get(DcMotorEx.class, "intake");
|
||||||
|
rejecter = hardwareMap.get(Servo.class, "rejecter");
|
||||||
|
|
||||||
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
|
||||||
|
|
||||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||||
|
|
||||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F);
|
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
|
||||||
shooter1.setVelocity(0);
|
shooterEncoder = shooter1;
|
||||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
|
||||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
|
||||||
shooter2.setVelocity(0);
|
|
||||||
|
|
||||||
hood = hardwareMap.get(Servo.class, "hood");
|
hood = hardwareMap.get(Servo.class, "hood");
|
||||||
|
|
||||||
turr1 = hardwareMap.get(Servo.class, "t1");
|
hoodPos = hardwareMap.get(AnalogInput.class, "hoodPos");
|
||||||
|
|
||||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
turr1 = hardwareMap.get(CRServo.class, "t1");
|
||||||
|
|
||||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos");
|
||||||
|
|
||||||
spin1 = hardwareMap.get(Servo.class, "spin2");
|
turr2 = hardwareMap.get(CRServo.class, "t2");
|
||||||
|
|
||||||
|
turr2Pos = hardwareMap.get(AnalogInput.class, "t2Pos");
|
||||||
|
|
||||||
|
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||||
|
|
||||||
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
|
||||||
|
|
||||||
spin2 = hardwareMap.get(Servo.class, "spin1");
|
spin2 = hardwareMap.get(CRServo.class, "spin2");
|
||||||
|
|
||||||
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
|
||||||
|
|
||||||
|
spin1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
spin2.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
pin0 = hardwareMap.get(DigitalChannel.class, "pin0");
|
||||||
|
|
||||||
|
pin1 = hardwareMap.get(DigitalChannel.class, "pin1");
|
||||||
|
|
||||||
|
pin2 = hardwareMap.get(DigitalChannel.class, "pin2");
|
||||||
|
|
||||||
|
pin3 = hardwareMap.get(DigitalChannel.class, "pin3");
|
||||||
|
|
||||||
|
pin4 = hardwareMap.get(DigitalChannel.class, "pin4");
|
||||||
|
|
||||||
|
pin5 = hardwareMap.get(DigitalChannel.class, "pin5");
|
||||||
|
|
||||||
|
analogInput = hardwareMap.get(AnalogInput.class, "analog");
|
||||||
|
|
||||||
|
analogInput2 = hardwareMap.get(AnalogInput.class, "analog2");
|
||||||
|
|
||||||
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
|
||||||
|
|
||||||
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
transferServo = hardwareMap.get(Servo.class, "transferServo");
|
||||||
@@ -112,7 +132,10 @@ public class Robot {
|
|||||||
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
|
||||||
|
|
||||||
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
|
||||||
|
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||||
|
|
||||||
|
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||||
|
|
||||||
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
|
||||||
|
|
||||||
@@ -120,14 +143,8 @@ 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) {
|
|
||||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
|
||||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
light = hardwareMap.get(Servo.class, "light");
|
|
||||||
voltage = hardwareMap.voltageSensor.iterator().next();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -6,93 +6,55 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class Servos {
|
public class Servos {
|
||||||
//PID constants
|
|
||||||
// TODO: get PIDF constants
|
|
||||||
public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
|
||||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
|
||||||
public static double spin_scalar = 1.112;
|
|
||||||
public static double spin_restPos = 0.155;
|
|
||||||
public static double turret_scalar = 1.009;
|
|
||||||
public static double turret_restPos = 0.0;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
|
|
||||||
PIDFController spinPID;
|
PIDFController spinPID;
|
||||||
|
|
||||||
PIDFController turretPID;
|
PIDFController turretPID;
|
||||||
|
|
||||||
private double prevSpinPos = 0.0;
|
//PID constants
|
||||||
private boolean firstSpinPos = true;
|
// TODO: get PIDF constants
|
||||||
|
public static double spinP = 3.4, spinI = 0, spinD = 0.075, spinF = 0.02;
|
||||||
|
public static double turrP = 4.0, turrI = 0.0, turrD = 0.0, turrF = 0.0;
|
||||||
|
|
||||||
private double prevTransferPos = 0.0;
|
public static double spin_scalar = 1.0086;
|
||||||
private boolean firstTransferPos = true;
|
public static double spin_restPos = 0.0;
|
||||||
|
public static double turret_scalar = 1.009;
|
||||||
private double prevHoodPos = 0.0;
|
public static double turret_restPos = 0.0;
|
||||||
private boolean firstHoodPos = true;
|
|
||||||
|
|
||||||
public Servos(HardwareMap hardwareMap) {
|
public Servos(HardwareMap hardwareMap) {
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
turretPID = new PIDFController(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
turretPID.setTolerance(0.001);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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 getSpinCmdPos() {
|
|
||||||
return prevSpinPos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public static boolean servoPosEqual(double pos1, double pos2) {
|
|
||||||
return (Math.abs(pos1 - pos2) < 0.005);
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setTransferPos(double pos) {
|
|
||||||
if (firstTransferPos || !servoPosEqual(pos, prevTransferPos)) {
|
|
||||||
robot.transferServo.setPosition(pos);
|
|
||||||
firstTransferPos = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
prevTransferPos = pos;
|
|
||||||
return pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setSpinPos(double pos) {
|
public double setSpinPos(double pos) {
|
||||||
if (firstSpinPos || !servoPosEqual(pos, prevSpinPos)) {
|
spinPID.setPIDF(spinP, spinI, spinD, spinF);
|
||||||
robot.spin1.setPosition(pos);
|
|
||||||
robot.spin2.setPosition(1-pos);
|
|
||||||
firstSpinPos = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
prevSpinPos = pos;
|
return spinPID.calculate(this.getSpinPos(), pos);
|
||||||
return pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setHoodPos(double pos){
|
|
||||||
if (firstHoodPos || !servoPosEqual(pos, prevHoodPos)) {
|
|
||||||
robot.hood.setPosition(pos);
|
|
||||||
firstHoodPos = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
prevHoodPos = pos;
|
|
||||||
return pos;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
public boolean spinEqual(double pos) {
|
||||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
return Math.abs(pos - this.getSpinPos()) < 0.02;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getTurrPos() {
|
public double getTurrPos() {
|
||||||
return 1.0;
|
return turret_scalar * ((robot.turr1Pos.getVoltage() - turret_restPos) / 3.3);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
public double setTurrPos(double pos) {
|
||||||
return 1.0;
|
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
||||||
|
|
||||||
|
return spinPID.calculate(this.getTurrPos(), pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
public boolean turretEqual(double pos) {
|
||||||
return true;
|
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,667 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
import com.qualcomm.robotcore.hardware.NormalizedColorSensor;
|
|
||||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.shootAllSpindexerSpeedIncrease;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
|
||||||
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_intakePos2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
|
||||||
|
|
||||||
import java.util.Objects;
|
|
||||||
|
|
||||||
public class Spindexer {
|
|
||||||
|
|
||||||
Robot robot;
|
|
||||||
Servos servos;
|
|
||||||
Flywheel flywheel;
|
|
||||||
MecanumDrive drive;
|
|
||||||
double lastKnownSpinPos = 0.0;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
|
|
||||||
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
|
||||||
|
|
||||||
double spinCurrentPos = 0.0;
|
|
||||||
|
|
||||||
public int commandedIntakePosition = 0;
|
|
||||||
|
|
||||||
public double distanceRearCenter = 0.0;
|
|
||||||
public double distanceFrontDriver = 0.0;
|
|
||||||
public double distanceFrontPassenger = 0.0;
|
|
||||||
|
|
||||||
public double spindexerWiggle = 0.01;
|
|
||||||
|
|
||||||
public double spindexerOuttakeWiggle = 0.01;
|
|
||||||
private double prevPos = 0.0;
|
|
||||||
public double spindexerPosOffset = 0.00;
|
|
||||||
public static int shootWaitMax = 4;
|
|
||||||
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
|
||||||
// For Use
|
|
||||||
enum RotatedBallPositionNames {
|
|
||||||
REARCENTER,
|
|
||||||
FRONTDRIVER,
|
|
||||||
FRONTPASSENGER
|
|
||||||
}
|
|
||||||
// Array of commandedIntakePositions with contents
|
|
||||||
// {RearCenter, FrontDriver, FrontPassenger}
|
|
||||||
static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}};
|
|
||||||
class spindexerBallRoatation {
|
|
||||||
int rearCenter = 0; // aka commanded Position
|
|
||||||
int frontDriver = 0;
|
|
||||||
int frontPassenger = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
enum IntakeState {
|
|
||||||
UNKNOWN_START,
|
|
||||||
UNKNOWN_MOVE,
|
|
||||||
UNKNOWN_DETECT,
|
|
||||||
INTAKE,
|
|
||||||
FINDNEXT,
|
|
||||||
MOVING,
|
|
||||||
FULL,
|
|
||||||
SHOOTNEXT,
|
|
||||||
SHOOTMOVING,
|
|
||||||
SHOOTWAIT,
|
|
||||||
SHOOT_ALL_PREP,
|
|
||||||
SHOOT_ALL_READY,
|
|
||||||
SHOOT_PREP_CONTINOUS,
|
|
||||||
SHOOT_CONTINOUS
|
|
||||||
}
|
|
||||||
|
|
||||||
int shootWaitCount = 0;
|
|
||||||
|
|
||||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
|
||||||
public IntakeState prevIntakeState = IntakeState.UNKNOWN_START;
|
|
||||||
public int unknownColorDetect = 0;
|
|
||||||
public enum BallColor {
|
|
||||||
UNKNOWN,
|
|
||||||
GREEN,
|
|
||||||
PURPLE
|
|
||||||
}
|
|
||||||
|
|
||||||
class BallPosition {
|
|
||||||
boolean isEmpty = true;
|
|
||||||
int foundEmpty = 0;
|
|
||||||
BallColor ballColor = BallColor.UNKNOWN;
|
|
||||||
}
|
|
||||||
|
|
||||||
BallPosition[] ballPositions = new BallPosition[3];
|
|
||||||
|
|
||||||
public boolean init () {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
public Spindexer(HardwareMap hardwareMap) {
|
|
||||||
robot = new Robot(hardwareMap);
|
|
||||||
servos = new Servos(hardwareMap);
|
|
||||||
flywheel = new Flywheel(hardwareMap);
|
|
||||||
//TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
|
||||||
|
|
||||||
lastKnownSpinPos = servos.getSpinPos();
|
|
||||||
|
|
||||||
ballPositions[0] = new BallPosition();
|
|
||||||
ballPositions[1] = new BallPosition();
|
|
||||||
ballPositions[2] = new BallPosition();
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
double[] outakePositions =
|
|
||||||
{spindexer_outtakeBall1+spindexerPosOffset,
|
|
||||||
spindexer_outtakeBall2+spindexerPosOffset,
|
|
||||||
spindexer_outtakeBall3+spindexerPosOffset};
|
|
||||||
|
|
||||||
double[] intakePositions =
|
|
||||||
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
|
||||||
|
|
||||||
public int counter = 0;
|
|
||||||
|
|
||||||
// private double getTimeSeconds ()
|
|
||||||
// {
|
|
||||||
// return (double) System.currentTimeMillis()/1000.0;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// public double getPos() {
|
|
||||||
// robot.spin1Pos.getVoltage();
|
|
||||||
// robot.spin1Pos.getMaxVoltage();
|
|
||||||
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
|
||||||
// }
|
|
||||||
|
|
||||||
// public void manageSpindexer() {
|
|
||||||
//
|
|
||||||
// }
|
|
||||||
|
|
||||||
public void resetBallPosition (int pos) {
|
|
||||||
ballPositions[pos].isEmpty = true;
|
|
||||||
ballPositions[pos].foundEmpty = 0;
|
|
||||||
ballPositions[pos].ballColor = BallColor.UNKNOWN;
|
|
||||||
distanceRearCenter = 61;
|
|
||||||
distanceFrontDriver = 61;
|
|
||||||
distanceFrontPassenger = 61;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void resetSpindexer () {
|
|
||||||
for (int i = 0; i < 3; i++) {
|
|
||||||
resetBallPosition(i);
|
|
||||||
}
|
|
||||||
currentIntakeState = IntakeState.UNKNOWN_START;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Detects if a ball is found and what color.
|
|
||||||
// Returns true is there was a new ball found in Position 1
|
|
||||||
// FIXIT: Reduce number of times that we read the color sensors for loop times.
|
|
||||||
public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
|
|
||||||
|
|
||||||
boolean newPos1Detection = false;
|
|
||||||
int spindexerBallPos = 0;
|
|
||||||
|
|
||||||
// Read Distances
|
|
||||||
double dRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
|
||||||
distanceRearCenter = (colorFilterAlpha * dRearCenter) + ((1-colorFilterAlpha) * distanceRearCenter);
|
|
||||||
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
|
|
||||||
if (distanceRearCenter < 60) {
|
|
||||||
|
|
||||||
// Mark Ball Found
|
|
||||||
newPos1Detection = true;
|
|
||||||
|
|
||||||
if (detectRearColor) {
|
|
||||||
// Detect which color
|
|
||||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
|
||||||
|
|
||||||
double gP = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
|
||||||
|
|
||||||
// FIXIT - Add filtering to improve accuracy.
|
|
||||||
if (gP >= 0.38) {
|
|
||||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// Position 2
|
|
||||||
// Find which ball position this is in the spindexer
|
|
||||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
|
||||||
if (distanceFrontDriver < 56) {
|
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
|
||||||
if (detectFrontColor) {
|
|
||||||
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
|
|
||||||
|
|
||||||
double gP = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
|
|
||||||
|
|
||||||
if (gP >= 0.4) {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
|
||||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
|
||||||
resetBallPosition(spindexerBallPos);
|
|
||||||
}
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty++;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// Position 3
|
|
||||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
|
|
||||||
if (distanceFrontPassenger < 29) {
|
|
||||||
|
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
|
||||||
if (detectFrontColor) {
|
|
||||||
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
|
|
||||||
|
|
||||||
double gP = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
|
|
||||||
|
|
||||||
if (gP >= 0.42) {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // green
|
|
||||||
} else {
|
|
||||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
|
||||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
|
||||||
resetBallPosition(spindexerBallPos);
|
|
||||||
}
|
|
||||||
ballPositions[spindexerBallPos].foundEmpty++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// TELE.addData("Velocity", velo);
|
|
||||||
// TELE.addLine("Detecting");
|
|
||||||
// TELE.addData("Distance 1", s1D);
|
|
||||||
// TELE.addData("Distance 2", s2D);
|
|
||||||
// TELE.addData("Distance 3", s3D);
|
|
||||||
// TELE.addData("B1", b1);
|
|
||||||
// TELE.addData("B2", b2);
|
|
||||||
// TELE.addData("B3", b3);
|
|
||||||
// TELE.update();
|
|
||||||
|
|
||||||
return newPos1Detection;
|
|
||||||
}
|
|
||||||
// Has code to unjam spindexer
|
|
||||||
private void moveSpindexerToPos(double pos) {
|
|
||||||
servos.setSpinPos(pos);
|
|
||||||
// double currentPos = servos.getSpinPos();
|
|
||||||
// if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){
|
|
||||||
// if (currentPos > pos){
|
|
||||||
// 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 = pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void stopSpindexer() {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getRearCenterLight() {
|
|
||||||
BallColor color = GetRearCenterColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
public double getDriverLight() {
|
|
||||||
BallColor color = GetFrontDriverColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getPassengerLight() {
|
|
||||||
BallColor color = GetFrontPassengerColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
public double ballCounterLight() {
|
|
||||||
int counter = 0;
|
|
||||||
if (!ballPositions[0].isEmpty) {
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
if (!ballPositions[1].isEmpty) {
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
if (!ballPositions[2].isEmpty) {
|
|
||||||
counter++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (counter == 3) {
|
|
||||||
return Light3;
|
|
||||||
} else if (counter == 2) {
|
|
||||||
return Light2;
|
|
||||||
} else if (counter == 1) {
|
|
||||||
return Light1;
|
|
||||||
} else {
|
|
||||||
return Light0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public boolean slotIsEmpty(int slot){
|
|
||||||
return !ballPositions[slot].isEmpty;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean isFull () {
|
|
||||||
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
|
||||||
}
|
|
||||||
|
|
||||||
private double intakeTicker = 0;
|
|
||||||
public boolean processIntake() {
|
|
||||||
|
|
||||||
switch (currentIntakeState) {
|
|
||||||
case UNKNOWN_START:
|
|
||||||
// For now just set position ONE if UNKNOWN
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
servos.setSpinPos(intakePositions[0]);
|
|
||||||
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
|
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case UNKNOWN_DETECT:
|
|
||||||
if (unknownColorDetect >5) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
} else {
|
|
||||||
//detectBalls(true, true);
|
|
||||||
unknownColorDetect++;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case INTAKE:
|
|
||||||
// Ready for intake and Detecting a New Ball
|
|
||||||
if (detectBalls(true, false)) {
|
|
||||||
ballPositions[commandedIntakePosition].isEmpty = false;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
} else {
|
|
||||||
// Maintain Position
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case FINDNEXT:
|
|
||||||
// Find Next Open Position and start movement
|
|
||||||
double currentSpindexerPos = servos.getSpinPos();
|
|
||||||
double commandedtravelDistance = 2.0;
|
|
||||||
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
|
||||||
//if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
|
||||||
if (ballPositions[0].isEmpty) {
|
|
||||||
// Position 1
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
//proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
|
||||||
//if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
|
||||||
else if (ballPositions[1].isEmpty) {
|
|
||||||
// Position 2
|
|
||||||
commandedIntakePosition = 1;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
//proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
|
||||||
else if (ballPositions[2].isEmpty) {
|
|
||||||
// Position 3
|
|
||||||
commandedIntakePosition = 2;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
|
||||||
}
|
|
||||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
|
||||||
// Full
|
|
||||||
//commandedIntakePosition = bestFitMotif();
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
|
||||||
}
|
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MOVING:
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
|
||||||
if (intakeTicker > 1){
|
|
||||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
|
||||||
stopSpindexer();
|
|
||||||
intakeTicker = 0;
|
|
||||||
} else {
|
|
||||||
intakeTicker++;
|
|
||||||
}
|
|
||||||
//detectBalls(false, false);
|
|
||||||
} else {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case FULL:
|
|
||||||
// Double Check Colors
|
|
||||||
detectBalls(false, false); // Minimize hardware calls
|
|
||||||
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
|
||||||
// Error handling found an empty spot, get it ready for a ball
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
}
|
|
||||||
// Maintain Position
|
|
||||||
spindexerWiggle *= -1.0;
|
|
||||||
servos.setSpinPos(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
|
|
||||||
servos.setSpinPos(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
|
|
||||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTNEXT:
|
|
||||||
// Find Next Open Position and start movement
|
|
||||||
if (!ballPositions[0].isEmpty) {
|
|
||||||
// Position 1
|
|
||||||
commandedIntakePosition = 0;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else if (!ballPositions[1].isEmpty) {
|
|
||||||
// Position 2
|
|
||||||
commandedIntakePosition = 1;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else if (!ballPositions[2].isEmpty) {
|
|
||||||
// Position 3
|
|
||||||
commandedIntakePosition = 2;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
|
||||||
} else {
|
|
||||||
// Empty return to intake state
|
|
||||||
currentIntakeState = IntakeState.FINDNEXT;
|
|
||||||
}
|
|
||||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTMOVING:
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
|
||||||
} else {
|
|
||||||
// Keep moving the spindexer
|
|
||||||
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOTWAIT:
|
|
||||||
// Stopping when we get to the new position
|
|
||||||
if (prevIntakeState != currentIntakeState) {
|
|
||||||
if (commandedIntakePosition==2) {
|
|
||||||
shootWaitMax = 5;
|
|
||||||
}
|
|
||||||
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.0;
|
|
||||||
servos.setSpinPos(outakePositions[commandedIntakePosition]+spindexerOuttakeWiggle);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOT_PREP_CONTINOUS:
|
|
||||||
if (servos.spinEqual(spinStartPos)){
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
|
||||||
} else {
|
|
||||||
servos.setSpinPos(spinStartPos);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case SHOOT_CONTINOUS:
|
|
||||||
ballPositions[0].isEmpty = false;
|
|
||||||
ballPositions[1].isEmpty = false;
|
|
||||||
ballPositions[2].isEmpty = false;
|
|
||||||
if (servos.getSpinPos() > spinEndPos){
|
|
||||||
currentIntakeState = IntakeState.FINDNEXT;
|
|
||||||
} else {
|
|
||||||
double spinPos = servos.getSpinCmdPos() + shootAllSpindexerSpeedIncrease;
|
|
||||||
if (spinPos > spinEndPos + 0.03){
|
|
||||||
spinPos = spinEndPos + 0.03;
|
|
||||||
}
|
|
||||||
servos.setSpinPos(spinPos);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
// Statements to execute if no case matches
|
|
||||||
}
|
|
||||||
|
|
||||||
prevIntakeState = currentIntakeState;
|
|
||||||
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
|
||||||
//TELE.update();
|
|
||||||
// Signal a successful intake
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setDesiredMotif (StateEnums.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 prepareShootAllContinous(){
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_PREP_CONTINOUS;
|
|
||||||
}
|
|
||||||
public void shootAll () {
|
|
||||||
ballPositions[0].isEmpty = false;
|
|
||||||
ballPositions[1].isEmpty = false;
|
|
||||||
ballPositions[2].isEmpty = false;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
|
||||||
}
|
|
||||||
public void shootAllContinous(){
|
|
||||||
ballPositions[0].isEmpty = false;
|
|
||||||
ballPositions[1].isEmpty = false;
|
|
||||||
ballPositions[2].isEmpty = false;
|
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
|
||||||
}
|
|
||||||
|
|
||||||
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) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOT_PREP_CONTINOUS) &&
|
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOT_CONTINOUS));
|
|
||||||
}
|
|
||||||
|
|
||||||
void shootAllToIntake () {
|
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
|
||||||
}
|
|
||||||
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
private double prevPow = 0.501;
|
|
||||||
public void setIntakePower(double pow){
|
|
||||||
if (prevPow != 0.501 && prevPow != pow){
|
|
||||||
robot.intake.setPower(pow);
|
|
||||||
}
|
|
||||||
prevPow = pow;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,231 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
|
||||||
|
|
||||||
public class Targeting {
|
|
||||||
// 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);
|
|
||||||
KNOWNTARGETING[1][3] = new Settings(2800.0, 0.68); // Real settings replaced with (0,3) new Settings (2800.0, 0.62);
|
|
||||||
KNOWNTARGETING[1][4] = new Settings(3000.0, 0.58); // Real setting replaced with (0,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);
|
|
||||||
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(2800.0, 0.62); // Real settings replaced with (1,3) new Settings (2900.0, 0.53);
|
|
||||||
KNOWNTARGETING[2][4] = new Settings(3000.0, 0.55); // real settings replaces with (1,4) new Settings (3100.0, 0.50);
|
|
||||||
KNOWNTARGETING[2][5] = new Settings(3200.0, 0.50); // real settings replaced with (1,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 final int TILE_UPPER_QUARTILE = 18;
|
|
||||||
public final int TILE_LOWER_QUARTILE = 6;
|
|
||||||
public double robotInchesX, robotInchesY = 0.0;
|
|
||||||
public int robotGridX, robotGridY = 0;
|
|
||||||
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 static boolean turretInterpolate = false;
|
|
||||||
|
|
||||||
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
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
|
||||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
|
||||||
} else {
|
|
||||||
robotGridY = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
|
||||||
robotGridX = 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 + ServoPositions.hoodOffset;
|
|
||||||
}
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,311 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
|
||||||
|
|
||||||
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 com.qualcomm.robotcore.util.ElapsedTime;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
|
||||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
|
||||||
|
|
||||||
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.39;
|
|
||||||
public static double turrMin = 0.15;
|
|
||||||
public static double turrMax = 0.85;
|
|
||||||
public static boolean limelightUsed = true;
|
|
||||||
|
|
||||||
public static double manualOffset = 0.0;
|
|
||||||
|
|
||||||
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;
|
|
||||||
//public static double B_PID_P = 0.105, B_PID_I = 0.0, B_PID_D = 0.0125;
|
|
||||||
public static double B_PID_P = 0.066, B_PID_I = 0.0, B_PID_D = 0.007;
|
|
||||||
Robot robot;
|
|
||||||
MultipleTelemetry TELE;
|
|
||||||
Limelight3A webcam;
|
|
||||||
double tx = 0.0;
|
|
||||||
double ty = 0.0;
|
|
||||||
double limelightPosX = 0.0;
|
|
||||||
double limelightPosY = 0.0;
|
|
||||||
LLResult result;
|
|
||||||
boolean bearingAligned = false;
|
|
||||||
private boolean lockOffset = false;
|
|
||||||
private int obeliskID = 0;
|
|
||||||
private double offset = 0.0;
|
|
||||||
private double currentTrackOffset = 0.0;
|
|
||||||
private double lightColor = Color.LightRed;
|
|
||||||
private int currentTrackCount = 0;
|
|
||||||
private double permanentOffset = 0.0;
|
|
||||||
private PIDController bearingPID;
|
|
||||||
|
|
||||||
private double prevTurretPos = 0.0;
|
|
||||||
private boolean firstTurretPos = true;
|
|
||||||
|
|
||||||
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 double getLightColor() {
|
|
||||||
return lightColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
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;
|
|
||||||
|
|
||||||
}
|
|
||||||
private double prevTurrPos = 0.501;
|
|
||||||
public void setTurret(double pos) {
|
|
||||||
if (prevTurrPos != 0.501 && prevTurrPos != pos){
|
|
||||||
robot.turr1.setPosition(pos);
|
|
||||||
robot.turr2.setPosition(1-pos);
|
|
||||||
}
|
|
||||||
prevTurrPos = pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
|
||||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
|
||||||
|
|
||||||
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;
|
|
||||||
final double COLOR_OK_TOLERANCE = 2.5;
|
|
||||||
|
|
||||||
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
|
||||||
bearingAligned = true;
|
|
||||||
lightColor = Color.LightBlue;
|
|
||||||
} else if (abs(targetTx) < COLOR_OK_TOLERANCE) {
|
|
||||||
bearingAligned = false;
|
|
||||||
lightColor = Color.LightPurple;
|
|
||||||
} else {
|
|
||||||
bearingAligned = false;
|
|
||||||
lightColor = Color.LightOrange;
|
|
||||||
}
|
|
||||||
|
|
||||||
// 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 && limelightUsed) {
|
|
||||||
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;
|
|
||||||
// }
|
|
||||||
lightColor = Color.LightRed;
|
|
||||||
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
|
|
||||||
setTurret(turretPos + manualOffset);
|
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- 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);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
@@ -6,26 +6,30 @@ repositories {
|
|||||||
maven { url = 'https://maven.brott.dev/' } //RR
|
maven { url = 'https://maven.brott.dev/' } //RR
|
||||||
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
||||||
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation 'org.firstinspires.ftc:Inspection:11.1.0'
|
implementation 'org.firstinspires.ftc:Inspection:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:Blocks:11.1.0'
|
implementation 'org.firstinspires.ftc:Blocks:11.0.0'
|
||||||
//noinspection Aligned16KB
|
implementation 'org.firstinspires.ftc:RobotCore:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:RobotCore:11.1.0'
|
implementation 'org.firstinspires.ftc:RobotServer:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:RobotServer:11.1.0'
|
implementation 'org.firstinspires.ftc:OnBotJava:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:OnBotJava:11.1.0'
|
implementation 'org.firstinspires.ftc:Hardware:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:Hardware:11.1.0'
|
implementation 'org.firstinspires.ftc:FtcCommon:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:FtcCommon:11.1.0'
|
implementation 'org.firstinspires.ftc:Vision:11.0.0'
|
||||||
implementation 'org.firstinspires.ftc:Vision:11.1.0'
|
|
||||||
implementation 'androidx.appcompat:appcompat:1.2.0'
|
implementation 'androidx.appcompat:appcompat:1.2.0'
|
||||||
|
|
||||||
|
|
||||||
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
|
||||||
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
implementation 'com.pedropathing:ftc:2.0.1' //PedroCore
|
||||||
|
implementation 'com.pedropathing:telemetry:0.0.6' //PedroTele
|
||||||
|
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
||||||
|
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
||||||
|
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
||||||
|
implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
@@ -36,5 +40,11 @@ dependencies {
|
|||||||
implementation("page.j5155.AdvantageScope:lite:v26.0.0") //AS
|
implementation("page.j5155.AdvantageScope:lite:v26.0.0") //AS
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -25,9 +25,5 @@ allprojects {
|
|||||||
}
|
}
|
||||||
|
|
||||||
repositories {
|
repositories {
|
||||||
repositories {
|
mavenCentral()
|
||||||
mavenCentral()
|
|
||||||
google()
|
|
||||||
maven { url 'https://maven.pedropathing.com' }
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user