Compare commits
48 Commits
93ed2208a9
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
7043274ebd | ||
|
|
bd05090afe | ||
|
|
369e379eb4 | ||
|
|
41853e9ad1 | ||
| c01edd9308 | |||
| ccfac3e123 | |||
| 395d4439db | |||
| 5f33cb4d41 | |||
| e92f11bc69 | |||
| 457eaf5feb | |||
| dc9886855b | |||
| 194100e3c8 | |||
| 64b2fed8d6 | |||
| 2ccd7f04f8 | |||
| 1ae4e1c3ed | |||
| 7a2b275e66 | |||
| 0264cf2c77 | |||
| f69bffc3ee | |||
| 09347ce479 | |||
| 102693d94a | |||
| c2e0b69c55 | |||
| 82c16b5402 | |||
| 5a456e211f | |||
| e87c5bb845 | |||
| a695f19cc6 | |||
| 1ad33fd45b | |||
| 56b61ee88b | |||
| 1ee40b472a | |||
| 3268d5cd02 | |||
| 44caad767b | |||
| dd1db74059 | |||
| 7161933d06 | |||
| 0f556a193f | |||
| 85989d54b9 | |||
| 2b9b0a140b | |||
| 18d9857b7a | |||
| 1c3100966c | |||
| 78c65c9d93 | |||
| 28816a6e34 | |||
| d0c34132de | |||
| 04ea56e31d | |||
| b616a41a08 | |||
| d18fedf8eb | |||
| f6b402dbf5 | |||
| 7d8dee7c3c | |||
| 038bd35bed | |||
| da944661a4 | |||
| a4755bf668 |
24
.slothLoad/SlothLoad.run.xml
Normal file
24
.slothLoad/SlothLoad.run.xml
Normal file
@@ -0,0 +1,24 @@
|
|||||||
|
<component name="ProjectRunConfigurationManager">
|
||||||
|
<configuration default="false" name="SlothLoad" type="GradleRunConfiguration" factoryName="Gradle">
|
||||||
|
<ExternalSystemSettings>
|
||||||
|
<option name="executionName" />
|
||||||
|
<option name="externalProjectPath" value="$PROJECT_DIR$" />
|
||||||
|
<option name="externalSystemIdString" value="GRADLE" />
|
||||||
|
<option name="scriptParameters" value="" />
|
||||||
|
<option name="taskDescriptions">
|
||||||
|
<list />
|
||||||
|
</option>
|
||||||
|
<option name="taskNames">
|
||||||
|
<list>
|
||||||
|
<option value="TeamCode:deploySloth" />
|
||||||
|
</list>
|
||||||
|
</option>
|
||||||
|
<option name="vmOptions" />
|
||||||
|
</ExternalSystemSettings>
|
||||||
|
<ExternalSystemDebugServerProcess>true</ExternalSystemDebugServerProcess>
|
||||||
|
<ExternalSystemReattachDebugProcess>true</ExternalSystemReattachDebugProcess>
|
||||||
|
<DebugAllEnabled>false</DebugAllEnabled>
|
||||||
|
<RunAsTest>false</RunAsTest>
|
||||||
|
<method v="2" />
|
||||||
|
</configuration>
|
||||||
|
</component>
|
||||||
75
.teamCodeRun/TeamCode.run.xml
Normal file
75
.teamCodeRun/TeamCode.run.xml
Normal file
@@ -0,0 +1,75 @@
|
|||||||
|
<component name="ProjectRunConfigurationManager">
|
||||||
|
<configuration default="false" name="TeamCode" type="AndroidRunConfigurationType" factoryName="Android App" activateToolWindowBeforeRun="false">
|
||||||
|
<module name="DecodeFTCMain.TeamCode" />
|
||||||
|
<option name="ANDROID_RUN_CONFIGURATION_SCHEMA_VERSION" value="1" />
|
||||||
|
<option name="DEPLOY" value="true" />
|
||||||
|
<option name="DEPLOY_APK_FROM_BUNDLE" value="false" />
|
||||||
|
<option name="DEPLOY_AS_INSTANT" value="false" />
|
||||||
|
<option name="ARTIFACT_NAME" value="" />
|
||||||
|
<option name="PM_INSTALL_OPTIONS" value="" />
|
||||||
|
<option name="ALL_USERS" value="false" />
|
||||||
|
<option name="ALWAYS_INSTALL_WITH_PM" value="false" />
|
||||||
|
<option name="ALLOW_ASSUME_VERIFIED" value="false" />
|
||||||
|
<option name="CLEAR_APP_STORAGE" value="false" />
|
||||||
|
<option name="DYNAMIC_FEATURES_DISABLED_LIST" value="" />
|
||||||
|
<option name="ACTIVITY_EXTRA_FLAGS" value="" />
|
||||||
|
<option name="MODE" value="default_activity" />
|
||||||
|
<option name="RESTORE_ENABLED" value="false" />
|
||||||
|
<option name="RESTORE_FILE" value="" />
|
||||||
|
<option name="RESTORE_FRESH_INSTALL_ONLY" value="false" />
|
||||||
|
<option name="CLEAR_LOGCAT" value="false" />
|
||||||
|
<option name="SHOW_LOGCAT_AUTOMATICALLY" value="false" />
|
||||||
|
<option name="TARGET_SELECTION_MODE" value="DEVICE_AND_SNAPSHOT_COMBO_BOX" />
|
||||||
|
<option name="SELECTED_CLOUD_MATRIX_CONFIGURATION_ID" value="-1" />
|
||||||
|
<option name="SELECTED_CLOUD_MATRIX_PROJECT_ID" value="" />
|
||||||
|
<option name="DEBUGGER_TYPE" value="Auto" />
|
||||||
|
<Auto>
|
||||||
|
<option name="USE_JAVA_AWARE_DEBUGGER" value="false" />
|
||||||
|
<option name="SHOW_STATIC_VARS" value="true" />
|
||||||
|
<option name="WORKING_DIR" value="" />
|
||||||
|
<option name="TARGET_LOGGING_CHANNELS" value="lldb process:gdb-remote packets" />
|
||||||
|
<option name="SHOW_OPTIMIZED_WARNING" value="true" />
|
||||||
|
<option name="ATTACH_ON_WAIT_FOR_DEBUGGER" value="false" />
|
||||||
|
<option name="DEBUG_SANDBOX_SDK" value="false" />
|
||||||
|
</Auto>
|
||||||
|
<Hybrid>
|
||||||
|
<option name="USE_JAVA_AWARE_DEBUGGER" value="false" />
|
||||||
|
<option name="SHOW_STATIC_VARS" value="true" />
|
||||||
|
<option name="WORKING_DIR" value="" />
|
||||||
|
<option name="TARGET_LOGGING_CHANNELS" value="lldb process:gdb-remote packets" />
|
||||||
|
<option name="SHOW_OPTIMIZED_WARNING" value="true" />
|
||||||
|
<option name="ATTACH_ON_WAIT_FOR_DEBUGGER" value="false" />
|
||||||
|
<option name="DEBUG_SANDBOX_SDK" value="false" />
|
||||||
|
</Hybrid>
|
||||||
|
<Java>
|
||||||
|
<option name="ATTACH_ON_WAIT_FOR_DEBUGGER" value="false" />
|
||||||
|
<option name="DEBUG_SANDBOX_SDK" value="false" />
|
||||||
|
</Java>
|
||||||
|
<Native>
|
||||||
|
<option name="USE_JAVA_AWARE_DEBUGGER" value="false" />
|
||||||
|
<option name="SHOW_STATIC_VARS" value="true" />
|
||||||
|
<option name="WORKING_DIR" value="" />
|
||||||
|
<option name="TARGET_LOGGING_CHANNELS" value="lldb process:gdb-remote packets" />
|
||||||
|
<option name="SHOW_OPTIMIZED_WARNING" value="true" />
|
||||||
|
<option name="ATTACH_ON_WAIT_FOR_DEBUGGER" value="false" />
|
||||||
|
<option name="DEBUG_SANDBOX_SDK" value="false" />
|
||||||
|
</Native>
|
||||||
|
<Profilers>
|
||||||
|
<option name="ADVANCED_PROFILING_ENABLED" value="false" />
|
||||||
|
<option name="STARTUP_PROFILING_ENABLED" value="false" />
|
||||||
|
<option name="STARTUP_CPU_PROFILING_ENABLED" value="false" />
|
||||||
|
<option name="STARTUP_CPU_PROFILING_CONFIGURATION_NAME" value="Java/Kotlin Method Sample (legacy)" />
|
||||||
|
<option name="STARTUP_NATIVE_MEMORY_PROFILING_ENABLED" value="false" />
|
||||||
|
<option name="NATIVE_MEMORY_SAMPLE_RATE_BYTES" value="2048" />
|
||||||
|
</Profilers>
|
||||||
|
<option name="DEEP_LINK" value="" />
|
||||||
|
<option name="ACTIVITY" value="" />
|
||||||
|
<option name="ACTIVITY_CLASS" value="" />
|
||||||
|
<option name="SEARCH_ACTIVITY_IN_GLOBAL_SCOPE" value="false" />
|
||||||
|
<option name="SKIP_ACTIVITY_VALIDATION" value="false" />
|
||||||
|
<method v="2">
|
||||||
|
<option name="Gradle.BeforeRunTask" enabled="true" tasks="removeSlothRemote" externalProjectPath="$PROJECT_DIR$/TeamCode" vmOptions="" scriptParameters="" />
|
||||||
|
<option name="Android.Gradle.BeforeRunTask" enabled="true" />
|
||||||
|
</method>
|
||||||
|
</configuration>
|
||||||
|
</component>
|
||||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -2,7 +2,6 @@ package org.firstinspires.ftc.teamcode.autonomous.actions;
|
|||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
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.spinStartPos;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
@@ -11,18 +10,23 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
|
|||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
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_in;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
import com.acmerobotics.roadrunner.Action;
|
import com.acmerobotics.roadrunner.Action;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
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.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||||
@@ -31,7 +35,8 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
|
|||||||
|
|
||||||
import java.util.Objects;
|
import java.util.Objects;
|
||||||
|
|
||||||
public class Actions{
|
@Config
|
||||||
|
public class AutoActions {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Servos servos;
|
Servos servos;
|
||||||
@@ -40,17 +45,18 @@ public class Actions{
|
|||||||
Spindexer spindexer;
|
Spindexer spindexer;
|
||||||
Targeting targeting;
|
Targeting targeting;
|
||||||
Targeting.Settings targetingSettings;
|
Targeting.Settings targetingSettings;
|
||||||
|
Light light;
|
||||||
Turret turret;
|
Turret turret;
|
||||||
private int driverSlotGreen = 0;
|
private int driverSlotGreen = 0;
|
||||||
private int passengerSlotGreen = 0;
|
private int passengerSlotGreen = 0;
|
||||||
private int rearSlotGreen = 0;
|
private int rearSlotGreen = 0;
|
||||||
private int mostGreenSlot = 0;
|
private int mostGreenSlot = 0;
|
||||||
private double firstSpindexShootPos = spinStartPos;
|
public static double firstSpindexShootPos = spinStartPos;
|
||||||
private boolean shootForward = true;
|
private boolean shootForward = true;
|
||||||
public static double firstShootTime = 0.3;
|
|
||||||
public int motif = 0;
|
public int motif = 0;
|
||||||
|
double spinEndPos = ServoPositions.spinEndPos;
|
||||||
|
|
||||||
public Actions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur){
|
public AutoActions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur, Light lig) {
|
||||||
this.robot = rob;
|
this.robot = rob;
|
||||||
this.drive = dri;
|
this.drive = dri;
|
||||||
this.TELE = tel;
|
this.TELE = tel;
|
||||||
@@ -60,8 +66,17 @@ public class Actions{
|
|||||||
this.targeting = tar;
|
this.targeting = tar;
|
||||||
this.targetingSettings = tS;
|
this.targetingSettings = tS;
|
||||||
this.turret = tur;
|
this.turret = tur;
|
||||||
|
this.light = lig;
|
||||||
}
|
}
|
||||||
public Action prepareShootAll(double colorSenseTime, double time, int motif_id) {
|
|
||||||
|
public Action prepareShootAll(
|
||||||
|
double colorSenseTime,
|
||||||
|
double time,
|
||||||
|
int motif_id,
|
||||||
|
double posX,
|
||||||
|
double posY,
|
||||||
|
double posH
|
||||||
|
) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
@@ -70,38 +85,61 @@ public class Actions{
|
|||||||
|
|
||||||
boolean decideGreenSlot = false;
|
boolean decideGreenSlot = false;
|
||||||
|
|
||||||
|
void spin1PosFirst() {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
|
}
|
||||||
|
|
||||||
|
void spin2PosFirst() {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
|
}
|
||||||
|
|
||||||
|
void reverseSpin2PosFirst() {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
|
}
|
||||||
|
|
||||||
|
void spin3PosFirst() {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
|
}
|
||||||
|
|
||||||
|
void oddSpin3PosFirst() {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
|
}
|
||||||
|
|
||||||
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
|
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||||
|
driverSlotGreen = 0;
|
||||||
|
passengerSlotGreen = 0;
|
||||||
|
rearSlotGreen = 0;
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
servos.setTransferPos(transferServo_out);
|
servos.setTransferPos(transferServo_out);
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.GOAL_LOCK);
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
manageShooter.run(telemetryPacket);
|
||||||
double robY = drive.localizer.getPose().position.y;
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
|
||||||
|
|
||||||
double goalX = -15;
|
TELE.addData("Most Green Slot", mostGreenSlot);
|
||||||
double goalY = 0;
|
TELE.addData("Driver Slot Greeness", driverSlotGreen);
|
||||||
|
TELE.addData("Passenger Slot Greeness", passengerSlotGreen);
|
||||||
double dx = robX - goalX; // delta x from robot to goal
|
TELE.addData("Rear Greeness", rearSlotGreen);
|
||||||
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();
|
TELE.update();
|
||||||
|
|
||||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
||||||
@@ -110,21 +148,38 @@ public class Actions{
|
|||||||
|
|
||||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
||||||
|
|
||||||
spindexer.detectBalls(true, true);
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
// Rear Center (Position 1)
|
||||||
driverSlotGreen++;
|
double distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
if (distanceRearCenter < 52) {
|
||||||
|
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||||
|
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||||
|
if (gP1 >= 0.38) {
|
||||||
|
rearSlotGreen++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
// Front Driver (Position 2)
|
||||||
passengerSlotGreen++;
|
double distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
if (distanceFrontDriver < 50) {
|
||||||
|
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
|
||||||
|
double gP2 = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
|
||||||
|
if (gP2 >= 0.4) {
|
||||||
|
driverSlotGreen++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
// Front Passenger (Position 3)
|
||||||
rearSlotGreen++;
|
double distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
if (distanceFrontPassenger < 29) {
|
||||||
|
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
|
||||||
|
double gP3 = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
|
||||||
|
if (gP3 >= 0.4) {
|
||||||
|
passengerSlotGreen++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
spindexer.setIntakePower(1);
|
spindexer.setIntakePower(-0.1);
|
||||||
|
|
||||||
decideGreenSlot = true;
|
decideGreenSlot = true;
|
||||||
|
|
||||||
@@ -145,43 +200,48 @@ public class Actions{
|
|||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else if (mostGreenSlot == 2) {
|
} else if (mostGreenSlot == 2) {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||||
shootForward = false;
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
} else {
|
} else {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
shootForward = false;
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
}
|
}
|
||||||
} else if (motif_id == 22) {
|
} else if (motif_id == 22) {
|
||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
shootForward = false;
|
|
||||||
} else if (mostGreenSlot == 2) {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
|
||||||
shootForward = false;
|
|
||||||
} else {
|
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
|
} else if (mostGreenSlot == 2) {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
|
} else {
|
||||||
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.03;
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||||
shootForward = false;
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
} else if (mostGreenSlot == 2) {
|
} else if (mostGreenSlot == 2) {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else {
|
} else {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
}
|
spinEndPos = 0.95; }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
||||||
// TELE.addData("MostGreenSlot", mostGreenSlot);
|
|
||||||
// TELE.update();
|
|
||||||
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
||||||
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
servos.setSpinPos(firstSpindexShootPos);
|
||||||
@@ -195,159 +255,65 @@ public class Actions{
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
|
public Action shootAllAuto(double shootTime, double spindexSpeed, double posX, double posY, double posH) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
int ticker = 1;
|
int ticker = 1;
|
||||||
|
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
double velo = vel;
|
|
||||||
int shooterTicker = 0;
|
int shooterTicker = 0;
|
||||||
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
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();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
spindexer.setIntakePower(-0.3);
|
spindexer.setIntakePower(-0.1);
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||||
|
light.update();
|
||||||
|
|
||||||
if (ticker == 1) {
|
if (ticker == 1) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
|
manageShooter = manageShooterAuto(shootTime, posX, posY, posH, false);
|
||||||
|
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
spindexer.setIntakePower(0);
|
manageShooter.run(telemetryPacket);
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
double prevSpinPos = servos.getSpinCmdPos();
|
||||||
|
|
||||||
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;
|
|
||||||
|
|
||||||
|
boolean end;
|
||||||
|
if (shootForward) {
|
||||||
|
end = servos.getSpinPos() > spinEndPos;
|
||||||
} else {
|
} else {
|
||||||
servos.setTransferPos(transferServo_out);
|
end = servos.getSpinPos() < spinEndPos;
|
||||||
|
|
||||||
spindexer.resetSpindexer();
|
|
||||||
spindexer.processIntake();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
public Action shootAllAuto(double shootTime, double spindexSpeed) {
|
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 1) {
|
||||||
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);
|
servos.setSpinPos(firstSpindexShootPos);
|
||||||
} else {
|
} else {
|
||||||
servos.setTransferPos(transferServo_in);
|
servos.setTransferPos(transferServo_in);
|
||||||
shooterTicker++;
|
shooterTicker++;
|
||||||
double prevSpinPos = servos.getSpinCmdPos();
|
Spindexer.whileShooting = true;
|
||||||
|
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
if (shootForward) {
|
|
||||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||||
} else {
|
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
servos.setTransferPos(transferServo_out);
|
servos.setTransferPos(transferServo_out);
|
||||||
|
Spindexer.whileShooting = false;
|
||||||
spindexer.resetSpindexer();
|
spindexer.resetSpindexer();
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
|
|
||||||
@@ -358,34 +324,119 @@ public class Actions{
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action intake(double intakeTime) {
|
public Action shootAllManual(
|
||||||
|
double shootTime,
|
||||||
|
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||||
|
double spindexSpeed,
|
||||||
|
double velStart,
|
||||||
|
double hoodStart,
|
||||||
|
double velEnd,
|
||||||
|
double hoodEnd,
|
||||||
|
double turr) {
|
||||||
|
return new Action() {
|
||||||
|
int ticker = 1;
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
int shooterTicker = 0;
|
||||||
|
Action manageShooter = null;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
spindexer.setIntakePower(-0.1);
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||||
|
light.update();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
stamp = System.currentTimeMillis();
|
||||||
|
manageShooter = manageShooterManual(shootTime, hoodMoveTime, velStart, hoodStart, velEnd, hoodEnd, turr);
|
||||||
|
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
manageShooter.run(telemetryPacket);
|
||||||
|
|
||||||
|
double prevSpinPos = servos.getSpinCmdPos();
|
||||||
|
|
||||||
|
boolean end;
|
||||||
|
if (shootForward) {
|
||||||
|
end = prevSpinPos > spinEndPos;
|
||||||
|
} else {
|
||||||
|
end = prevSpinPos < spinEndPos;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (System.currentTimeMillis() - stamp < shootTime * 1000 && !end) {
|
||||||
|
servos.setTransferPos(transferServo_in);
|
||||||
|
shooterTicker++;
|
||||||
|
Spindexer.whileShooting = true;
|
||||||
|
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
|
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||||
|
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
|
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
servos.setTransferPos(transferServo_out);
|
||||||
|
Spindexer.whileShooting = false;
|
||||||
|
spindexer.resetSpindexer();
|
||||||
|
spindexer.processIntake();
|
||||||
|
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action intake(
|
||||||
|
double time,
|
||||||
|
double posX,
|
||||||
|
double posY,
|
||||||
|
double posH
|
||||||
|
) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
|
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
spindexer.setIntakePower(1);
|
spindexer.setIntakePower(1);
|
||||||
|
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||||
|
light.update();
|
||||||
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
TELE.addData("Full?", spindexer.isFull());
|
manageShooter.run(telemetryPacket);
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
return ((System.currentTimeMillis() - stamp) < (intakeTime * 1000)) && !spindexer.isFull();
|
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
|
||||||
|
servos.setSpinPos(spindexer_intakePos1);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private boolean detectingObelisk = false;
|
||||||
|
|
||||||
public Action detectObelisk(
|
public Action detectObelisk(
|
||||||
double time,
|
double time,
|
||||||
double posX,
|
double posX,
|
||||||
@@ -403,41 +454,44 @@ public class Actions{
|
|||||||
|
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
int prevMotif = 0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
detectingObelisk = true;
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
Pose2d currentPose = drive.localizer.getPose();
|
||||||
|
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
robot.limelight.pipelineSwitch(1);
|
turret.pipelineSwitch(1);
|
||||||
|
ticker++;
|
||||||
}
|
}
|
||||||
|
|
||||||
ticker++;
|
|
||||||
motif = turret.detectObelisk();
|
motif = turret.detectObelisk();
|
||||||
|
|
||||||
|
if (prevMotif == motif){
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
prevMotif = motif;
|
||||||
|
|
||||||
turret.setTurret(turrPos);
|
turret.setTurret(turrPos);
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull() || ticker > 10;
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
teleStart = currentPose;
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
|
||||||
|
|
||||||
if (shouldFinish){
|
if (shouldFinish) {
|
||||||
if (redAlliance){
|
if (redAlliance) {
|
||||||
robot.limelight.pipelineSwitch(4);
|
turret.pipelineSwitch(4);
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
turret.pipelineSwitch(2);
|
||||||
}
|
}
|
||||||
|
detectingObelisk = false;
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
return true;
|
return true;
|
||||||
@@ -447,150 +501,127 @@ public class Actions{
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
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(
|
public Action manageShooterAuto(
|
||||||
double time,
|
double time,
|
||||||
double posX,
|
double posX,
|
||||||
double posY,
|
double posY,
|
||||||
double posXTolerance,
|
double posH,
|
||||||
double posYTolerance
|
boolean flywheelSensor
|
||||||
) {
|
) {
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
return new Action() {
|
||||||
|
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
|
final boolean timeFallback = (time != 0.501);
|
||||||
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
Pose2d currentPose = drive.localizer.getPose();
|
Pose2d currentPose = drive.localizer.getPose();
|
||||||
|
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
|
|
||||||
|
if (redAlliance) {
|
||||||
|
turret.pipelineSwitch(4);
|
||||||
|
light.setManualLightColor(Color.LightRed);
|
||||||
|
} else {
|
||||||
|
turret.pipelineSwitch(2);
|
||||||
|
light.setManualLightColor(Color.LightBlue);
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
double robotX = currentPose.position.x;
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
double robotY = currentPose.position.y;
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
double robotHeading = currentPose.heading.toDouble();
|
||||||
|
|
||||||
double goalX = -15;
|
double goalX = -15;
|
||||||
double goalY = 0;
|
double goalY = 0;
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
double dx = robotX - goalX; // delta x from robot to goal
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
double dy = robotY - goalY; // delta y from robot to goal
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
Pose2d deltaPose;
|
||||||
|
if (posX != 0.501) {
|
||||||
|
deltaPose = new Pose2d(posX, posY, Math.toRadians(posH));
|
||||||
|
} else {
|
||||||
|
deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||||
|
}
|
||||||
|
Turret.limelightUsed = true;
|
||||||
|
|
||||||
|
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
targetingSettings = targeting.calculateSettings
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
(robotX, robotY, robotHeading, 0.0, false);
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
if (!detectingObelisk) {
|
||||||
|
turret.trackGoal(deltaPose);
|
||||||
|
}
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
servos.setHoodPos(targetingSettings.hoodAngle);
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
double voltage = robot.voltage.getVoltage();
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
boolean shouldFinish = timeDone || (flywheel.getSteady() && flywheelSensor);
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
|
||||||
|
|
||||||
boolean shouldFinish = timeDone || xDone || yDone;
|
teleStart = currentPose;
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
return !shouldFinish;
|
return !shouldFinish;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Wait(double time) {
|
||||||
|
return new Action() {
|
||||||
|
boolean ticker = false;
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (!ticker) {
|
||||||
|
stamp = System.currentTimeMillis();
|
||||||
|
ticker = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return (System.currentTimeMillis() - stamp < time * 1000);
|
||||||
|
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action manageFlywheelAuto(
|
public Action manageShooterManual(
|
||||||
double time,
|
double maxTime,
|
||||||
double posX,
|
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||||
double posY,
|
double velStart,
|
||||||
double posXTolerance,
|
double hoodStart,
|
||||||
double posYTolerance
|
double velEnd,
|
||||||
|
double hoodEnd,
|
||||||
|
double turr
|
||||||
) {
|
) {
|
||||||
|
|
||||||
boolean timeFallback = (time != 0.501);
|
|
||||||
boolean posXFallback = (posX != 0.501);
|
|
||||||
boolean posYFallback = (posY != 0.501);
|
|
||||||
|
|
||||||
return new Action() {
|
return new Action() {
|
||||||
|
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
|
final boolean timeFallback = (maxTime != 0.501);
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
@@ -603,43 +634,41 @@ public class Actions{
|
|||||||
|
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
double robotX = drive.localizer.getPose().position.x;
|
double robotX = currentPose.position.x;
|
||||||
double robotY = drive.localizer.getPose().position.y;
|
double robotY = currentPose.position.y;
|
||||||
|
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
double robotHeading = currentPose.heading.toDouble();
|
||||||
|
|
||||||
double goalX = -15;
|
double goalX = -15;
|
||||||
double goalY = 0;
|
double goalY = 0;
|
||||||
|
|
||||||
double dx = robotX - goalX; // delta x from robot to goal
|
double dx = robotX - goalX; // delta x from robot to goal
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
double dy = robotY - goalY; // delta y from robot to goal
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
Pose2d deltaPose;
|
||||||
|
if (turr == 0.501) {
|
||||||
|
deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||||
|
if (!detectingObelisk) {
|
||||||
|
turret.trackGoal(deltaPose);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
turret.setTurret(turr);
|
||||||
|
}
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
servos.setHoodPos(hoodStart + ((hoodEnd - hoodStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1)));
|
||||||
|
double vel = velStart + (velEnd - velStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1);
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
double voltage = robot.voltage.getVoltage();
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
flywheel.manageFlywheel(vel);
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > maxTime * 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;
|
teleStart = currentPose;
|
||||||
drive.updatePoseEstimate();
|
|
||||||
|
|
||||||
teleStart = drive.localizer.getPose();
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
|
||||||
TELE.addData("Hood", robot.hood.getPosition());
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
return !shouldFinish;
|
return !timeDone;
|
||||||
|
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
@@ -1,23 +1,29 @@
|
|||||||
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.acmerobotics.roadrunner.Pose2d;
|
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class Back_Poses {
|
public class Back_Poses {
|
||||||
public static double rLeaveX = 90, rLeaveY = 80, rLeaveH = 50.1;
|
public static double rLeaveX = 90, rLeaveY = 50, rLeaveH = 50.1;
|
||||||
public static double bLeaveX = 90, bLeaveY = -80, bLeaveH = -50;
|
public static double bLeaveX = 90, bLeaveY = -50, bLeaveH = -50;
|
||||||
|
|
||||||
public static double rShootX = 95, rShootY = 85, rShootH = 90;
|
public static double rShootX = 100, rShootY = 55, rShootH = 90;
|
||||||
public static double bShootX = 95, bShootY = -85, bShootH = -90;
|
public static double bShootX = 100, bShootY = -55, bShootH = -90;
|
||||||
|
|
||||||
public static double rStackPickupAX = 75, rStackPickupAY = 53, rStackPickupAH = 140;
|
public static double rStackPickupAX = 73, rStackPickupAY = 51, rStackPickupAH = 140;
|
||||||
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
|
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
|
||||||
|
|
||||||
public static double rStackPickupBX = 50, rStackPickupBY = 78, rStackPickupBH = 140.1;
|
public static double rStackPickupBX = 53, rStackPickupBY = 71, rStackPickupBH = 140.1;
|
||||||
public static double bStackPickupBX = 50, bStackPickupBY = -78, bStackPickupBH = -140.1;
|
public static double bStackPickupBX = 55, bStackPickupBY = -73, bStackPickupBH = -140.1;
|
||||||
|
|
||||||
public static Pose2d autoStart = new Pose2d(0, 0, 0); // TODO: find this position
|
public static double rPickupGateX = 50, rPickupGateY = 83, rPickupGateH = 140;
|
||||||
|
public static double bPickupGateX = 70, bPickupGateY = -90, bPickupGateH = -140;
|
||||||
|
public static double pickupGateXB = 84, pickupGateYB = 76, pickupGateHB = 140;
|
||||||
|
public static double pickupGateXC = 50, pickupGateYC = 83, pickupGateHC = 190;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public static double autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 50;
|
||||||
|
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -50;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,39 +8,55 @@ public class Front_Poses {
|
|||||||
|
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
|
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 bx1 = 20, by1 = -0.5, bh1 = -0.1;
|
||||||
|
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
||||||
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
||||||
|
|
||||||
public static double rx2b = 23, ry2b = 36, rh2b = 140.1;
|
public static double rx2b = 21, ry2b = 34, rh2b = 140.1;
|
||||||
public static double bx2b = 19, by2b = -40, bh2b = -140.1;
|
public static double bx2b = 23, by2b = -36, bh2b = -140.1;
|
||||||
|
|
||||||
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
||||||
public static double bx3a = 55, by3a = -39, bh3a = -140;
|
public static double bx3a = 55, by3a = -39, bh3a = -140;
|
||||||
|
|
||||||
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
||||||
public static double bx3aG = 55, by3aG = -43, bh3aG = -140;
|
public static double bx3aG = 60, by3aG = -34, bh3aG = -140;
|
||||||
|
|
||||||
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
||||||
public static double bx3b = 41, by3b = -59, bh3b = -140.1;
|
public static double bx3b = 36, by3b = -58, bh3b = -140.1;
|
||||||
|
|
||||||
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
||||||
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
||||||
|
|
||||||
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
||||||
public static double bx4b = 47, by4b = -85, bh4b = -140.1;
|
public static double bx4b = 50, by4b = -78, bh4b = -140.1;
|
||||||
|
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
||||||
|
|
||||||
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
||||||
public static double bShootX = 40, bShootY = 0, bShootH = -50;
|
public static double bShootX = 40, bShootY = -10, bShootH = -50;
|
||||||
|
|
||||||
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
|
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
|
||||||
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
|
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
|
||||||
|
|
||||||
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 50;
|
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 55;
|
||||||
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -50;
|
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -55;
|
||||||
|
|
||||||
|
public static double rShoot0X = 53, rShoot0Y = 10.1, rShoot0H = 80.1;
|
||||||
|
public static double bShoot0X = 53, bShoot0Y = -10.1, bShoot0H = -80.1;
|
||||||
|
|
||||||
|
public static double rShootGateX = 50, rShootGateY = 10, rShootGateH = 90;
|
||||||
|
public static double bShootGateX = 50, bShootGateY = -10, bShootGateH = -90;
|
||||||
|
|
||||||
|
public static double rLeaveGateX = 40, rLeaveGateY = -7, rLeaveGateH = 55;
|
||||||
|
public static double bLeaveGateX = 40, bLeaveGateY = 7, bLeaveGateH = -55;
|
||||||
|
|
||||||
|
public static double rPickupGateAX = 31, rPickupGateAY = 53, rPickupGateAH = 150;
|
||||||
|
public static double bPickupGateAX = 24, bPickupGateAY = -50, bPickupGateAH = -150;
|
||||||
|
|
||||||
|
public static double rPickupGateBX = 38, rPickupGateBY = 62, rPickupGateBH = 210;
|
||||||
|
public static double bPickupGateBX = 38, bPickupGateBY = -68, bPickupGateBH = -180;
|
||||||
|
public static double pickupGateCX = 34, pickupGateCY = 58, pickupGateCH = 220;
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -5,19 +5,19 @@ 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.18; //0.13;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.27; //0.33;//0.5;
|
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.46; //0.53;//0.66;
|
public static double spindexer_intakePos3 = 0.56; //0.53;//0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
|
public static double spindexer_outtakeBall3 = 0.84; //0.65; //0.24;
|
||||||
public static double spindexer_outtakeBall3b = 0.15; //0.65; //0.24;
|
public static double spindexer_outtakeBall3b = 0.27; //0.65; //0.24;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
public static double spindexer_outtakeBall2 = 0.66; //0.46; //0.6;
|
||||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
public static double spindexer_outtakeBall1 = 0.47; //0.27; //0.4;
|
||||||
public static double spinStartPos = 0.22;
|
public static double spinStartPos = 0.10;
|
||||||
public static double spinEndPos = 0.85;
|
public static double spinEndPos = 0.95;
|
||||||
|
|
||||||
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
||||||
|
|
||||||
@@ -27,19 +27,21 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double hoodAuto = 0.27;
|
public static double hoodAuto = 0.27;
|
||||||
|
|
||||||
public static double hoodOffset = -0.05;
|
public static double hoodOffset = -0.04; // offset from 0.93
|
||||||
|
|
||||||
public static double turret_redClose = 0.42;
|
public static double turret_redClose = 0;
|
||||||
public static double turret_blueClose = 0.38;
|
public static double turret_blueClose = 0;
|
||||||
|
|
||||||
// These values are ADDED to turrDefault
|
// These values are ADDED to turrDefault
|
||||||
public static double redObeliskTurrPos1 = 0.12;
|
public static double redObeliskTurrPos0 = -0.35;
|
||||||
public static double redObeliskTurrPos2 = 0.13;
|
public static double redObeliskTurrPos1 = 0.15;
|
||||||
public static double redObeliskTurrPos3 = 0.14;
|
public static double redObeliskTurrPos2 = 0.16;
|
||||||
public static double blueObeliskTurrPos1 = -0.12;
|
public static double redObeliskTurrPos3 = 0.17;
|
||||||
public static double blueObeliskTurrPos2 = -0.13;
|
public static double blueObeliskTurrPos0 = 0.35;
|
||||||
public static double blueObeliskTurrPos3 = -0.14;
|
public static double blueObeliskTurrPos1 = -0.15;
|
||||||
public static double redTurretShootPos = 0.1;
|
public static double blueObeliskTurrPos2 = -0.16;
|
||||||
public static double blueTurretShootPos = -0.14;
|
public static double blueObeliskTurrPos3 = -0.17;
|
||||||
|
public static double redTurretShootPos = 0.05;
|
||||||
|
public static double blueTurretShootPos = -0.05;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -5,7 +5,9 @@ import androidx.annotation.NonNull;
|
|||||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
import com.acmerobotics.roadrunner.*;
|
import com.acmerobotics.roadrunner.AccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
|
import com.acmerobotics.roadrunner.Actions;
|
||||||
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
||||||
import com.acmerobotics.roadrunner.DualNum;
|
import com.acmerobotics.roadrunner.DualNum;
|
||||||
import com.acmerobotics.roadrunner.HolonomicController;
|
import com.acmerobotics.roadrunner.HolonomicController;
|
||||||
@@ -14,12 +16,20 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
|
|||||||
import com.acmerobotics.roadrunner.MotorFeedforward;
|
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
import com.acmerobotics.roadrunner.Pose2dDual;
|
import com.acmerobotics.roadrunner.Pose2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||||
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
||||||
|
import com.acmerobotics.roadrunner.ProfileParams;
|
||||||
|
import com.acmerobotics.roadrunner.Rotation2d;
|
||||||
import com.acmerobotics.roadrunner.Time;
|
import com.acmerobotics.roadrunner.Time;
|
||||||
import com.acmerobotics.roadrunner.TimeTrajectory;
|
import com.acmerobotics.roadrunner.TimeTrajectory;
|
||||||
import com.acmerobotics.roadrunner.TimeTurn;
|
import com.acmerobotics.roadrunner.TimeTurn;
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
|
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
|
||||||
import com.acmerobotics.roadrunner.TurnConstraints;
|
import com.acmerobotics.roadrunner.TurnConstraints;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2d;
|
||||||
|
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||||
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.VelConstraint;
|
import com.acmerobotics.roadrunner.VelConstraint;
|
||||||
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
||||||
import com.acmerobotics.roadrunner.ftc.Encoder;
|
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||||
@@ -46,13 +56,131 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
|
|||||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
||||||
|
|
||||||
import java.lang.Math;
|
|
||||||
import java.util.Arrays;
|
import java.util.Arrays;
|
||||||
import java.util.LinkedList;
|
import java.util.LinkedList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
public final class MecanumDrive {
|
public final class MecanumDrive {
|
||||||
|
public static Params PARAMS = new Params();
|
||||||
|
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||||
|
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||||
|
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||||
|
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||||
|
public final VelConstraint defaultVelConstraint =
|
||||||
|
new MinVelConstraint(Arrays.asList(
|
||||||
|
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||||
|
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||||
|
));
|
||||||
|
public final AccelConstraint defaultAccelConstraint =
|
||||||
|
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||||
|
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||||
|
public final VoltageSensor voltageSensor;
|
||||||
|
public final LazyImu lazyImu;
|
||||||
|
public final Localizer localizer;
|
||||||
|
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||||
|
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||||
|
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||||
|
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||||
|
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||||
|
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||||
|
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||||
|
|
||||||
|
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||||
|
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: make sure your config has motors with these names (or change them)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||||
|
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||||
|
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||||
|
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||||
|
|
||||||
|
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
|
||||||
|
// TODO: reverse motor directions if needed
|
||||||
|
//
|
||||||
|
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||||
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
|
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||||
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
|
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||||
|
|
||||||
|
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setDrivePowers(PoseVelocity2d powers) {
|
||||||
|
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||||
|
PoseVelocity2dDual.constant(powers, 1));
|
||||||
|
|
||||||
|
double maxPowerMag = 1;
|
||||||
|
for (DualNum<Time> power : wheelVels.all()) {
|
||||||
|
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||||
|
}
|
||||||
|
|
||||||
|
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||||
|
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||||
|
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||||
|
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||||
|
}
|
||||||
|
|
||||||
|
public PoseVelocity2d updatePoseEstimate() {
|
||||||
|
PoseVelocity2d vel = localizer.update();
|
||||||
|
poseHistory.add(localizer.getPose());
|
||||||
|
|
||||||
|
while (poseHistory.size() > 100) {
|
||||||
|
poseHistory.removeFirst();
|
||||||
|
}
|
||||||
|
|
||||||
|
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||||
|
|
||||||
|
return vel;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void drawPoseHistory(Canvas c) {
|
||||||
|
double[] xPoints = new double[poseHistory.size()];
|
||||||
|
double[] yPoints = new double[poseHistory.size()];
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (Pose2d t : poseHistory) {
|
||||||
|
xPoints[i] = t.position.x;
|
||||||
|
yPoints[i] = t.position.y;
|
||||||
|
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
c.setStrokeWidth(1);
|
||||||
|
c.setStroke("#3F51B5");
|
||||||
|
c.strokePolyline(xPoints, yPoints);
|
||||||
|
}
|
||||||
|
|
||||||
|
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||||
|
return new TrajectoryActionBuilder(
|
||||||
|
TurnAction::new,
|
||||||
|
FollowTrajectoryAction::new,
|
||||||
|
new TrajectoryBuilderParams(
|
||||||
|
1e-6,
|
||||||
|
new ProfileParams(
|
||||||
|
0.25, 0.1, 1e-2
|
||||||
|
)
|
||||||
|
),
|
||||||
|
beginPose, 0.0,
|
||||||
|
defaultTurnConstraints,
|
||||||
|
defaultVelConstraint, defaultAccelConstraint
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
public static class Params {
|
public static class Params {
|
||||||
// IMU orientation
|
// IMU orientation
|
||||||
// TODO: fill in these values based on
|
// TODO: fill in these values based on
|
||||||
@@ -64,62 +192,33 @@ public final class MecanumDrive {
|
|||||||
|
|
||||||
// drive model parameters
|
// drive model parameters
|
||||||
public double inPerTick = 0.001978956;
|
public double inPerTick = 0.001978956;
|
||||||
public double lateralInPerTick = 0.0013863732202094405;
|
public double lateralInPerTick = 0.001367789463080072;
|
||||||
public double trackWidthTicks = 6488.883015684446;
|
public double trackWidthTicks = 6913.070212622687;
|
||||||
|
|
||||||
// feedforward parameters (in tick units)
|
// feedforward parameters (in tick units)
|
||||||
public double kS = 1.2147826978829488;
|
public double kS = 1.23;
|
||||||
public double kV = 0.00032;
|
public double kV = 0.00035;
|
||||||
public double kA = 0.000046;
|
public double kA = 0.00008;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// path profile parameters (in inches)
|
||||||
public double maxWheelVel = 180;
|
public double maxWheelVel = 70;
|
||||||
public double minProfileAccel = -40;
|
public double minProfileAccel = -40;
|
||||||
public double maxProfileAccel = 180;
|
public double maxProfileAccel = 70;
|
||||||
|
|
||||||
// turn profile parameters (in radians)
|
// turn profile parameters (in radians)
|
||||||
public double maxAngVel = 4* Math.PI; // shared with path
|
public double maxAngVel = 2 *Math.PI; // shared with path
|
||||||
public double maxAngAccel = 4* Math.PI;
|
public double maxAngAccel = 2 * Math.PI;
|
||||||
|
|
||||||
// path controller gains
|
// path controller gains
|
||||||
public double axialGain = 4;
|
public double axialGain = 6.0;
|
||||||
public double lateralGain = 4;
|
public double lateralGain = 6.0;
|
||||||
public double headingGain = 4; // shared with turn
|
public double headingGain = 6.0; // shared with turn
|
||||||
|
|
||||||
public double axialVelGain = 0.0;
|
public double axialVelGain = 0.0;
|
||||||
public double lateralVelGain = 0.0;
|
public double lateralVelGain = 0.0;
|
||||||
public double headingVelGain = 0.0; // shared with turn
|
public double headingVelGain = 0.0; // shared with turn
|
||||||
}
|
}
|
||||||
|
|
||||||
public static Params PARAMS = new Params();
|
|
||||||
|
|
||||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
|
||||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
|
||||||
|
|
||||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
|
||||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
|
||||||
public final VelConstraint defaultVelConstraint =
|
|
||||||
new MinVelConstraint(Arrays.asList(
|
|
||||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
|
||||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
|
||||||
));
|
|
||||||
public final AccelConstraint defaultAccelConstraint =
|
|
||||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
|
||||||
|
|
||||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
|
||||||
|
|
||||||
public final VoltageSensor voltageSensor;
|
|
||||||
|
|
||||||
public final LazyImu lazyImu;
|
|
||||||
|
|
||||||
public final Localizer localizer;
|
|
||||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
|
||||||
|
|
||||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
|
||||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
|
||||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
|
||||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
|
||||||
|
|
||||||
public class DriveLocalizer implements Localizer {
|
public class DriveLocalizer implements Localizer {
|
||||||
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
||||||
public final IMU imu;
|
public final IMU imu;
|
||||||
@@ -144,13 +243,13 @@ public final class MecanumDrive {
|
|||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void setPose(Pose2d pose) {
|
public Pose2d getPose() {
|
||||||
this.pose = pose;
|
return pose;
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public Pose2d getPose() {
|
public void setPose(Pose2d pose) {
|
||||||
return pose;
|
this.pose = pose;
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
@@ -216,63 +315,10 @@ public final class MecanumDrive {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
|
||||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
|
||||||
|
|
||||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
|
||||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO: make sure your config has motors with these names (or change them)
|
|
||||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
|
||||||
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
|
||||||
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
|
||||||
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
|
||||||
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
|
||||||
|
|
||||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
|
||||||
|
|
||||||
// TODO: reverse motor directions if needed
|
|
||||||
//
|
|
||||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
|
|
||||||
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
|
|
||||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
|
||||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
|
||||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
|
||||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
|
||||||
|
|
||||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
|
||||||
|
|
||||||
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
|
||||||
|
|
||||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
|
||||||
}
|
|
||||||
|
|
||||||
public void setDrivePowers(PoseVelocity2d powers) {
|
|
||||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
|
||||||
PoseVelocity2dDual.constant(powers, 1));
|
|
||||||
|
|
||||||
double maxPowerMag = 1;
|
|
||||||
for (DualNum<Time> power : wheelVels.all()) {
|
|
||||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
|
||||||
}
|
|
||||||
|
|
||||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
|
||||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
|
||||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
|
||||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
|
||||||
}
|
|
||||||
|
|
||||||
public final class FollowTrajectoryAction implements Action {
|
public final class FollowTrajectoryAction implements Action {
|
||||||
public final TimeTrajectory timeTrajectory;
|
public final TimeTrajectory timeTrajectory;
|
||||||
private double beginTs = -1;
|
|
||||||
|
|
||||||
private final double[] xPoints, yPoints;
|
private final double[] xPoints, yPoints;
|
||||||
|
private double beginTs = -1;
|
||||||
|
|
||||||
public FollowTrajectoryAction(TimeTrajectory t) {
|
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||||
timeTrajectory = t;
|
timeTrajectory = t;
|
||||||
@@ -299,7 +345,16 @@ public final class MecanumDrive {
|
|||||||
t = Actions.now() - beginTs;
|
t = Actions.now() - beginTs;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (t >= timeTrajectory.duration) {
|
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||||
|
|
||||||
|
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||||
|
|
||||||
|
if ((t >= timeTrajectory.duration && error.position.norm() < 1
|
||||||
|
&& robotVelRobot.linearVel.norm() < 0.5)
|
||||||
|
|| t >= timeTrajectory.duration + 0.01) {
|
||||||
leftFront.setPower(0);
|
leftFront.setPower(0);
|
||||||
leftBack.setPower(0);
|
leftBack.setPower(0);
|
||||||
rightBack.setPower(0);
|
rightBack.setPower(0);
|
||||||
@@ -308,10 +363,6 @@ public final class MecanumDrive {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
|
||||||
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
|
||||||
|
|
||||||
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
|
||||||
|
|
||||||
PoseVelocity2dDual<Time> command = new HolonomicController(
|
PoseVelocity2dDual<Time> command = new HolonomicController(
|
||||||
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
||||||
@@ -342,7 +393,6 @@ public final class MecanumDrive {
|
|||||||
p.put("y", localizer.getPose().position.y);
|
p.put("y", localizer.getPose().position.y);
|
||||||
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
||||||
|
|
||||||
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
|
||||||
p.put("xError", error.position.x);
|
p.put("xError", error.position.x);
|
||||||
p.put("yError", error.position.y);
|
p.put("yError", error.position.y);
|
||||||
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
||||||
@@ -450,51 +500,4 @@ public final class MecanumDrive {
|
|||||||
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public PoseVelocity2d updatePoseEstimate() {
|
|
||||||
PoseVelocity2d vel = localizer.update();
|
|
||||||
poseHistory.add(localizer.getPose());
|
|
||||||
|
|
||||||
while (poseHistory.size() > 100) {
|
|
||||||
poseHistory.removeFirst();
|
|
||||||
}
|
|
||||||
|
|
||||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
|
||||||
|
|
||||||
|
|
||||||
return vel;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void drawPoseHistory(Canvas c) {
|
|
||||||
double[] xPoints = new double[poseHistory.size()];
|
|
||||||
double[] yPoints = new double[poseHistory.size()];
|
|
||||||
|
|
||||||
int i = 0;
|
|
||||||
for (Pose2d t : poseHistory) {
|
|
||||||
xPoints[i] = t.position.x;
|
|
||||||
yPoints[i] = t.position.y;
|
|
||||||
|
|
||||||
i++;
|
|
||||||
}
|
|
||||||
|
|
||||||
c.setStrokeWidth(1);
|
|
||||||
c.setStroke("#3F51B5");
|
|
||||||
c.strokePolyline(xPoints, yPoints);
|
|
||||||
}
|
|
||||||
|
|
||||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
|
||||||
return new TrajectoryActionBuilder(
|
|
||||||
TurnAction::new,
|
|
||||||
FollowTrajectoryAction::new,
|
|
||||||
new TrajectoryBuilderParams(
|
|
||||||
1e-6,
|
|
||||||
new ProfileParams(
|
|
||||||
0.25, 0.1, 1e-2
|
|
||||||
)
|
|
||||||
),
|
|
||||||
beginPose, 0.0,
|
|
||||||
defaultTurnConstraints,
|
|
||||||
defaultVelConstraint, defaultAccelConstraint
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,10 +16,11 @@ import java.util.Objects;
|
|||||||
@Config
|
@Config
|
||||||
public final class PinpointLocalizer implements Localizer {
|
public final class PinpointLocalizer implements Localizer {
|
||||||
public static class Params {
|
public static class Params {
|
||||||
public double parYTicks = -3765.023079161767; // y position of the parallel encoder (in tick units)
|
public double parYTicks = -3758.6603115671537; // y position of the parallel encoder (in tick units)
|
||||||
public double perpXTicks = -1962.6377639490684; // x position of the perpendicular encoder (in tick units)
|
public double perpXTicks = -2088.4296466563774; // x position of the perpendicular encoder (in tick units)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public static Params PARAMS = new Params();
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
public final GoBildaPinpointDriver driver;
|
public final GoBildaPinpointDriver driver;
|
||||||
@@ -48,6 +49,8 @@ public final class PinpointLocalizer implements Localizer {
|
|||||||
txWorldPinpoint = initialPose;
|
txWorldPinpoint = initialPose;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void setPose(Pose2d pose) {
|
public void setPose(Pose2d pose) {
|
||||||
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
||||||
|
|||||||
@@ -2,7 +2,6 @@ package org.firstinspires.ftc.teamcode.teleop;
|
|||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
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 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.Targeting.turretInterpolate;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
|
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
|
||||||
@@ -46,9 +45,9 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
public double vel = 3000;
|
public double vel = 3000;
|
||||||
public boolean autoVel = true;
|
public boolean autoVel = true;
|
||||||
public boolean targetingHood = true;
|
public boolean targetingHood = true;
|
||||||
public boolean autoHood = true;
|
// public boolean autoHood = true;
|
||||||
public double shootStamp = 0.0;
|
public double shootStamp = 0.0;
|
||||||
boolean fixedTurret = false;
|
// boolean fixedTurret = false;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Light light;
|
Light light;
|
||||||
@@ -66,16 +65,18 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
boolean reject = false;
|
boolean reject = false;
|
||||||
double xOffset = 0.0;
|
double xOffset = 0.0;
|
||||||
double yOffset = 0.0;
|
double yOffset = 0.0;
|
||||||
double headingOffset = 0.0;
|
double hOffset = 0.0;
|
||||||
|
// double headingOffset = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
boolean autoSpintake = false;
|
// boolean autoSpintake = false;
|
||||||
boolean enableSpindexerManager = true;
|
boolean enableSpindexerManager = true;
|
||||||
|
|
||||||
boolean overrideTurr = false;
|
// boolean overrideTurr = false;
|
||||||
|
|
||||||
int intakeTicker = 0;
|
int intakeTicker = 0;
|
||||||
private boolean shootAll = false;
|
private boolean shootAll = false;
|
||||||
|
boolean relocalize = false;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -112,17 +113,17 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
light.setState(StateEnums.LightState.MANUAL);
|
light.setState(StateEnums.LightState.MANUAL);
|
||||||
limelightUsed = true;
|
limelightUsed = true;
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
|
||||||
while (opModeInInit()) {
|
while (opModeInInit()) {
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
robot.limelight.pipelineSwitch(4);
|
turret.pipelineSwitch(4);
|
||||||
light.setManualLightColor(Color.LightRed);
|
light.setManualLightColor(Color.LightRed);
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
turret.pipelineSwitch(2);
|
||||||
light.setManualLightColor(Color.LightBlue);
|
light.setManualLightColor(Color.LightBlue);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
robot.light.setPosition(1);
|
||||||
|
|
||||||
light.update();
|
light.update();
|
||||||
}
|
}
|
||||||
@@ -141,12 +142,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//DRIVETRAIN:
|
//DRIVETRAIN:
|
||||||
|
|
||||||
drivetrain.drive(
|
drivetrain.drive(-gamepad1.right_stick_y, gamepad1.right_stick_x, gamepad1.left_stick_x, gamepad1.left_trigger);
|
||||||
-gamepad1.right_stick_y,
|
|
||||||
gamepad1.right_stick_x,
|
|
||||||
gamepad1.left_stick_x,
|
|
||||||
gamepad1.left_trigger
|
|
||||||
);
|
|
||||||
|
|
||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
|
|
||||||
@@ -155,10 +151,10 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
light.setState(StateEnums.LightState.BALL_COUNT);
|
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||||
|
|
||||||
} else if (gamepad2.triangle){
|
} else if (gamepad2.triangle) {
|
||||||
light.setState(StateEnums.LightState.BALL_COLOR);
|
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
light.setState(StateEnums.LightState.GOAL_LOCK);
|
light.setState(StateEnums.LightState.GOAL_LOCK);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -166,10 +162,11 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
double robX = drive.localizer.getPose().position.x;
|
||||||
double robY = drive.localizer.getPose().position.y;
|
double robY = drive.localizer.getPose().position.y;
|
||||||
|
double robH = drive.localizer.getPose().heading.toDouble();
|
||||||
|
|
||||||
double robotX = robX - xOffset;
|
double robotX = robX + xOffset;
|
||||||
double robotY = robY - yOffset;
|
double robotY = robY + yOffset;
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
double robotHeading = robH + hOffset;
|
||||||
|
|
||||||
double goalX = -15;
|
double goalX = -15;
|
||||||
double goalY = 0;
|
double goalY = 0;
|
||||||
@@ -178,12 +175,25 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
double dy = robotY - goalY; // delta y from robot to goal
|
double dy = robotY - goalY; // delta y from robot to goal
|
||||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||||
|
|
||||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
targetingSettings = targeting.calculateSettings(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
||||||
(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
//RELOCALIZATION
|
||||||
|
|
||||||
|
if (gamepad2.squareWasPressed()) {
|
||||||
|
relocalize = !relocalize;
|
||||||
|
gamepad2.rumble(500);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (relocalize) {
|
||||||
|
turret.relocalize();
|
||||||
|
xOffset = -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset) - robX;
|
||||||
|
yOffset = (turret.getLimelightX() * 39.3701) - robY;
|
||||||
|
hOffset = (Math.toRadians(turret.getLimelightH())) - robH;
|
||||||
|
} else {
|
||||||
|
turret.trackGoal(deltaPose);
|
||||||
|
}
|
||||||
|
|
||||||
//VELOCITY AUTOMATIC
|
//VELOCITY AUTOMATIC
|
||||||
if (autoVel) {
|
if (autoVel) {
|
||||||
@@ -210,11 +220,12 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//SHOOTER:
|
//SHOOTER:
|
||||||
double voltage = robot.voltage.getVoltage();
|
double voltage = robot.voltage.getVoltage();
|
||||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||||
flywheel.manageFlywheel(vel);
|
flywheel.manageFlywheel(vel);
|
||||||
|
|
||||||
//HOOD:
|
//HOOD:
|
||||||
|
|
||||||
|
|
||||||
if (targetingHood) {
|
if (targetingHood) {
|
||||||
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
|
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
|
||||||
} else {
|
} else {
|
||||||
@@ -251,7 +262,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (enableSpindexerManager) {
|
if (enableSpindexerManager) {
|
||||||
//if (!shootAll) {
|
//if (!shootAll) {
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
@@ -262,7 +272,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
spindexer.setIntakePower(1);
|
spindexer.setIntakePower(1);
|
||||||
} else if (gamepad1.cross) {
|
} else if (gamepad1.cross) {
|
||||||
spindexer.setIntakePower(-1);
|
spindexer.setIntakePower(-1);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
spindexer.setIntakePower(0);
|
spindexer.setIntakePower(0);
|
||||||
}
|
}
|
||||||
@@ -284,15 +293,11 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
if (shooterTicker == 0) {
|
if (shooterTicker == 0) {
|
||||||
spindexer.prepareShootAllContinous();
|
spindexer.prepareShootAllContinous();
|
||||||
//TELE.addLine("preparing to shoot");
|
//TELE.addLine("preparing to shoot");
|
||||||
// } else if (shooterTicker == 2) {
|
// else if (shooterTicker == 2) {
|
||||||
// //servo.setTransferPos(transferServo_in);
|
// //servo.setTransferPos(transferServo_in);
|
||||||
// spindexer.shootAll();
|
// spindexer.shootAll();
|
||||||
// TELE.addLine("starting to shoot");
|
// TELE.addLine("starting to shoot");
|
||||||
} else if (!spindexer.shootAllComplete()) {
|
} else if (spindexer.shootAllComplete()) {
|
||||||
servo.setTransferPos(transferServo_in);
|
|
||||||
//TELE.addLine("shoot");
|
|
||||||
} else {
|
|
||||||
servo.setTransferPos(transferServo_out);
|
|
||||||
//spindexPos = spindexer_intakePos1;
|
//spindexPos = spindexer_intakePos1;
|
||||||
shootAll = false;
|
shootAll = false;
|
||||||
spindexer.resetSpindexer();
|
spindexer.resetSpindexer();
|
||||||
@@ -345,18 +350,22 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// Targeting Debug
|
// Targeting Debug
|
||||||
TELE.addData("robotX", robotX);
|
TELE.addData("robotX", robotX);
|
||||||
TELE.addData("robotY", robotY);
|
TELE.addData("robotY", robotY);
|
||||||
TELE.addData("robotInchesX", targeting.robotInchesX);
|
TELE.addData("robot H", robotHeading);
|
||||||
TELE.addData("robotInchesY", targeting.robotInchesY);
|
// TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||||
TELE.addData("Targeting Interpolate", turretInterpolate);
|
// TELE.addData("robotInchesY", targeting.robotInchesY);
|
||||||
|
// TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||||
TELE.addData("Targeting GridX", targeting.robotGridX);
|
TELE.addData("Targeting GridX", targeting.robotGridX);
|
||||||
TELE.addData("Targeting GridY", targeting.robotGridY);
|
TELE.addData("Targeting GridY", targeting.robotGridY);
|
||||||
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||||
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||||
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||||
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
// TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
||||||
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
||||||
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
||||||
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
|
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
|
||||||
|
TELE.addData("Tag Pos X", -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset));
|
||||||
|
TELE.addData("Tag Pos Y", turret.getLimelightX() * 39.3701);
|
||||||
|
TELE.addData("Tag Pos H", Math.toRadians(turret.getLimelightH()));
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
|
|||||||
@@ -7,6 +7,7 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
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 com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
@@ -28,16 +29,20 @@ public class ColorTest extends LinearOpMode {
|
|||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
while(opModeIsActive()){
|
while(opModeIsActive()){
|
||||||
double green1 = robot.color1.getNormalizedColors().green;
|
|
||||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
|
||||||
double red1 = robot.color1.getNormalizedColors().red;
|
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||||
|
|
||||||
|
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||||
|
|
||||||
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
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", gP1);
|
||||||
TELE.addData("Color1 distance (mm)", color1Distance);
|
TELE.addData("Color1 distance (mm)", color1Distance);
|
||||||
|
|
||||||
|
|
||||||
// ----- COLOR 2 -----
|
// ----- COLOR 2 -----
|
||||||
double green2 = robot.color2.getNormalizedColors().green;
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@ package org.firstinspires.ftc.teamcode.tests;
|
|||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
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.spinStartPos;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
@@ -37,7 +38,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
public static double P = 255.0;
|
public static double P = 255.0;
|
||||||
public static double I = 0.0;
|
public static double I = 0.0;
|
||||||
public static double D = 0.0;
|
public static double D = 0.0;
|
||||||
public static double F = 90;
|
public static double F = 75;
|
||||||
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;
|
||||||
@@ -128,9 +129,9 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
if (enableHoodAutoOpen) {
|
if (enableHoodAutoOpen) {
|
||||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)) + hoodOffset);
|
||||||
} else {
|
} else {
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos + hoodOffset);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,110 @@
|
|||||||
|
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.ftc.Actions;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.autonomous.actions.AutoActions;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||||
|
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
|
||||||
|
@TeleOp
|
||||||
|
public class SortingTest extends LinearOpMode {
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
MecanumDrive drive;
|
||||||
|
Servos servos;
|
||||||
|
Spindexer spindexer;
|
||||||
|
Flywheel flywheel;
|
||||||
|
Turret turret;
|
||||||
|
Targeting targeting;
|
||||||
|
Targeting.Settings targetingSettings;
|
||||||
|
AutoActions autoActions;
|
||||||
|
Light light;
|
||||||
|
@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);
|
||||||
|
|
||||||
|
turret = new Turret(robot, TELE, robot.limelight);
|
||||||
|
|
||||||
|
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
|
|
||||||
|
light = Light.getInstance();
|
||||||
|
|
||||||
|
light.init(robot.light, spindexer, turret);
|
||||||
|
|
||||||
|
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
||||||
|
|
||||||
|
int motif = 21;
|
||||||
|
boolean intaking = true;
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
|
while (opModeIsActive()){
|
||||||
|
spindexer.setIntakePower(1);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
if (gamepad1.crossWasPressed()){
|
||||||
|
motif = 21;
|
||||||
|
} else if (gamepad1.squareWasPressed()){
|
||||||
|
motif = 22;
|
||||||
|
} else if (gamepad1.triangleWasPressed()){
|
||||||
|
motif = 23;
|
||||||
|
}
|
||||||
|
flywheel.manageFlywheel(2500);
|
||||||
|
|
||||||
|
if (gamepad1.leftBumperWasPressed()){
|
||||||
|
intaking = false;
|
||||||
|
Actions.runBlocking(
|
||||||
|
autoActions.prepareShootAll(
|
||||||
|
3,
|
||||||
|
5,
|
||||||
|
motif,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501
|
||||||
|
)
|
||||||
|
);
|
||||||
|
} else if (gamepad1.rightBumperWasPressed()){
|
||||||
|
intaking = false;
|
||||||
|
Actions.runBlocking(
|
||||||
|
autoActions.shootAllAuto(
|
||||||
|
3.5,
|
||||||
|
0.014,
|
||||||
|
0.501,
|
||||||
|
0.501,
|
||||||
|
0.501
|
||||||
|
)
|
||||||
|
);
|
||||||
|
intaking = true;
|
||||||
|
} else if (intaking){
|
||||||
|
spindexer.processIntake();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -12,15 +12,13 @@ public class Flywheel {
|
|||||||
public double velo1 = 0.0;
|
public double velo1 = 0.0;
|
||||||
public double velo2 = 0.0;
|
public double velo2 = 0.0;
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double previousTargetVelocity = 0.0;
|
|
||||||
double powPID = 0.0;
|
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public Flywheel (HardwareMap hardwareMap) {
|
public Flywheel (HardwareMap hardwareMap) {
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
shooterPIDF1 = new PIDFCoefficients
|
shooterPIDF1 = new PIDFCoefficients
|
||||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
|
||||||
shooterPIDF2 = new PIDFCoefficients
|
shooterPIDF2 = new PIDFCoefficients
|
||||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getVelo () {
|
public double getVelo () {
|
||||||
@@ -38,8 +36,8 @@ public class Flywheel {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Set the robot PIDF for the next cycle.
|
// Set the robot PIDF for the next cycle.
|
||||||
private double prevF = 0.501;
|
private double prevF = 0;
|
||||||
public static int voltagePIDFDifference = 5;
|
public static double voltagePIDFDifference = 0.8;
|
||||||
public void setPIDF(double p, double i, double d, double f) {
|
public void setPIDF(double p, double i, double d, double f) {
|
||||||
shooterPIDF1.p = p;
|
shooterPIDF1.p = p;
|
||||||
shooterPIDF1.i = i;
|
shooterPIDF1.i = i;
|
||||||
@@ -52,6 +50,7 @@ public class Flywheel {
|
|||||||
if (Math.abs(prevF - f) > voltagePIDFDifference){
|
if (Math.abs(prevF - f) > voltagePIDFDifference){
|
||||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||||
|
prevF = f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -61,26 +60,23 @@ public class Flywheel {
|
|||||||
// Convert from Ticks per Second to RPM
|
// Convert from Ticks per Second to RPM
|
||||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||||
|
|
||||||
public double manageFlywheel(double commandedVelocity) {
|
public void manageFlywheel(double commandedVelocity) {
|
||||||
|
|
||||||
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
|
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
|
||||||
targetVelocity = commandedVelocity;
|
targetVelocity = commandedVelocity;
|
||||||
// Add code here to set PIDF based on desired RPM
|
// Add code here to set PIDF based on desired RPM
|
||||||
//robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
//robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||||
//robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
//robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||||
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);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
|
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
|
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||||
|
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||||
|
velo = Math.max(velo1, velo2);
|
||||||
// really should be a running average of the last 5
|
// really should be a running average of the last 5
|
||||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
steady = (Math.abs(commandedVelocity - velo) < 50);
|
||||||
|
|
||||||
return powPID;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public void update()
|
public void update()
|
||||||
|
|||||||
@@ -12,7 +12,7 @@ public final class Light {
|
|||||||
|
|
||||||
private static Light instance;
|
private static Light instance;
|
||||||
public static double ballColorCycleTime = 1000; //in ms
|
public static double ballColorCycleTime = 1000; //in ms
|
||||||
public static double restingTime = 150; //in ms
|
public static double restingTime = 125; //in ms
|
||||||
|
|
||||||
private Servo lightServo;
|
private Servo lightServo;
|
||||||
private LightState state = LightState.DISABLED;
|
private LightState state = LightState.DISABLED;
|
||||||
|
|||||||
@@ -7,10 +7,10 @@ public class MeasuringLoopTimes {
|
|||||||
private double minLoopTime = 999999999999.0;
|
private double minLoopTime = 999999999999.0;
|
||||||
|
|
||||||
private double maxLoopTime = 0.0;
|
private double maxLoopTime = 0.0;
|
||||||
private double mainLoopTime = 0.0;
|
double mainLoopTime = 0.0;
|
||||||
|
|
||||||
private double MeasurementStart = 0.0;
|
private double MeasurementStart = 0.0;
|
||||||
private double currentTime = 0.0;
|
double currentTime = 0.0;
|
||||||
|
|
||||||
private double avgLoopTime = 0.0;
|
private double avgLoopTime = 0.0;
|
||||||
private int avgLoopTimeTicker = 0;
|
private int avgLoopTimeTicker = 0;
|
||||||
|
|||||||
@@ -1,11 +1,9 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
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;
|
||||||
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;
|
||||||
@@ -31,11 +29,11 @@ public class Robot {
|
|||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
public DcMotorEx transfer;
|
public DcMotorEx transfer;
|
||||||
public PIDFCoefficients shooterPIDF;
|
public PIDFCoefficients shooterPIDF;
|
||||||
public double shooterPIDF_P = 255.0;
|
public static double shooterPIDF_P = 255;
|
||||||
public double shooterPIDF_I = 0.0;
|
public static double shooterPIDF_I = 0.0;
|
||||||
public double shooterPIDF_D = 0.0;
|
public static double shooterPIDF_D = 0.0;
|
||||||
public double shooterPIDF_F = 90;
|
public static double shooterPIDF_F = 75;
|
||||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
// public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||||
public DcMotorEx shooter1;
|
public DcMotorEx shooter1;
|
||||||
public DcMotorEx shooter2;
|
public DcMotorEx shooter2;
|
||||||
public Servo hood;
|
public Servo hood;
|
||||||
|
|||||||
@@ -1,5 +1,7 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
@@ -12,8 +14,6 @@ public class Servos {
|
|||||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||||
public static double spin_scalar = 1.112;
|
public static double spin_scalar = 1.112;
|
||||||
public static double spin_restPos = 0.155;
|
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;
|
||||||
@@ -49,14 +49,13 @@ public class Servos {
|
|||||||
return (Math.abs(pos1 - pos2) < 0.005);
|
return (Math.abs(pos1 - pos2) < 0.005);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setTransferPos(double pos) {
|
public void setTransferPos(double pos) {
|
||||||
if (firstTransferPos || !servoPosEqual(pos, prevTransferPos)) {
|
if (firstTransferPos || !servoPosEqual(pos, prevTransferPos)) {
|
||||||
robot.transferServo.setPosition(pos);
|
robot.transferServo.setPosition(pos);
|
||||||
firstTransferPos = false;
|
firstTransferPos = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
prevTransferPos = pos;
|
prevTransferPos = pos;
|
||||||
return pos;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setSpinPos(double pos) {
|
public double setSpinPos(double pos) {
|
||||||
@@ -70,29 +69,16 @@ public class Servos {
|
|||||||
return pos;
|
return pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setHoodPos(double pos){
|
public void setHoodPos(double pos){
|
||||||
if (firstHoodPos || !servoPosEqual(pos, prevHoodPos)) {
|
if (firstHoodPos || !servoPosEqual(pos, prevHoodPos)) {
|
||||||
robot.hood.setPosition(pos);
|
robot.hood.setPosition(pos + hoodOffset);
|
||||||
firstHoodPos = false;
|
firstHoodPos = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
prevHoodPos = pos;
|
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.03;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getTurrPos() {
|
|
||||||
return 1.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
|
||||||
return 1.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,6 +16,8 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
|
|||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
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_outtakeBall2;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
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.utils.Servos.spinD;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||||
@@ -52,6 +54,9 @@ public class Spindexer {
|
|||||||
private double prevPos = 0.0;
|
private double prevPos = 0.0;
|
||||||
public double spindexerPosOffset = 0.00;
|
public double spindexerPosOffset = 0.00;
|
||||||
public static int shootWaitMax = 4;
|
public static int shootWaitMax = 4;
|
||||||
|
public static boolean whileShooting = false;
|
||||||
|
public static int waitFirstBallTicks = 4;
|
||||||
|
private int shootTicks = 0;
|
||||||
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
||||||
// For Use
|
// For Use
|
||||||
enum RotatedBallPositionNames {
|
enum RotatedBallPositionNames {
|
||||||
@@ -182,7 +187,7 @@ public class Spindexer {
|
|||||||
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
||||||
|
|
||||||
// Position 1
|
// Position 1
|
||||||
if (distanceRearCenter < 60) {
|
if (distanceRearCenter < 48) {
|
||||||
|
|
||||||
// Mark Ball Found
|
// Mark Ball Found
|
||||||
newPos1Detection = true;
|
newPos1Detection = true;
|
||||||
@@ -204,7 +209,7 @@ public class Spindexer {
|
|||||||
// Position 2
|
// Position 2
|
||||||
// Find which ball position this is in the spindexer
|
// Find which ball position this is in the spindexer
|
||||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||||
if (distanceFrontDriver < 56) {
|
if (distanceFrontDriver < 50) {
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
if (detectFrontColor) {
|
if (detectFrontColor) {
|
||||||
@@ -530,18 +535,26 @@ public class Spindexer {
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case SHOOT_PREP_CONTINOUS:
|
case SHOOT_PREP_CONTINOUS:
|
||||||
if (servos.spinEqual(spinStartPos)){
|
if (shootTicks > waitFirstBallTicks){
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
||||||
|
shootTicks++;
|
||||||
|
} else if (servos.spinEqual(spinStartPos)){
|
||||||
|
shootTicks++;
|
||||||
|
servos.setTransferPos(transferServo_in);
|
||||||
} else {
|
} else {
|
||||||
servos.setSpinPos(spinStartPos);
|
servos.setSpinPos(spinStartPos);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case SHOOT_CONTINOUS:
|
case SHOOT_CONTINOUS:
|
||||||
|
whileShooting = true;
|
||||||
ballPositions[0].isEmpty = false;
|
ballPositions[0].isEmpty = false;
|
||||||
ballPositions[1].isEmpty = false;
|
ballPositions[1].isEmpty = false;
|
||||||
ballPositions[2].isEmpty = false;
|
ballPositions[2].isEmpty = false;
|
||||||
if (servos.getSpinPos() > spinEndPos){
|
if (servos.getSpinPos() > spinEndPos){
|
||||||
|
whileShooting = false;
|
||||||
|
servos.setTransferPos(transferServo_out);
|
||||||
|
shootTicks = 0;
|
||||||
currentIntakeState = IntakeState.FINDNEXT;
|
currentIntakeState = IntakeState.FINDNEXT;
|
||||||
} else {
|
} else {
|
||||||
double spinPos = servos.getSpinCmdPos() + shootAllSpindexerSpeedIncrease;
|
double spinPos = servos.getSpinCmdPos() + shootAllSpindexerSpeedIncrease;
|
||||||
@@ -658,8 +671,10 @@ public class Spindexer {
|
|||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
||||||
}
|
}
|
||||||
private double prevPow = 0.501;
|
private double prevPow = 0.501;
|
||||||
|
private boolean firstIntakePow = true;
|
||||||
public void setIntakePower(double pow){
|
public void setIntakePower(double pow){
|
||||||
if (prevPow != 0.501 && prevPow != pow){
|
if (firstIntakePow || prevPow != pow){
|
||||||
|
firstIntakePow = false;
|
||||||
robot.intake.setPower(pow);
|
robot.intake.setPower(pow);
|
||||||
}
|
}
|
||||||
prevPow = pow;
|
prevPow = pow;
|
||||||
|
|||||||
@@ -82,13 +82,19 @@ public class Targeting {
|
|||||||
public Targeting() {
|
public Targeting() {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
double cos54 = Math.cos(Math.toRadians(-54));
|
||||||
|
double sin54 = Math.sin(Math.toRadians(-54));
|
||||||
|
|
||||||
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
||||||
Settings recommendedSettings = new Settings(0.0, 0.0);
|
Settings recommendedSettings = new Settings(0.0, 0.0);
|
||||||
|
if (!redAlliance){
|
||||||
double cos45 = Math.cos(Math.toRadians(-45));
|
sin54 = Math.sin(Math.toRadians(54));
|
||||||
double sin45 = Math.sin(Math.toRadians(-45));
|
} else {
|
||||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
sin54 = Math.sin(Math.toRadians(-54));
|
||||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
}
|
||||||
|
// TODO: test these values determined from the fmap
|
||||||
|
double rotatedY = (robotX + cancelOffsetX) * sin54 + (robotY + cancelOffsetY) * cos54;
|
||||||
|
double rotatedX = (robotX + cancelOffsetX) * cos54 - (robotY + cancelOffsetY) * sin54;
|
||||||
|
|
||||||
// Convert robot coordinates to inches
|
// Convert robot coordinates to inches
|
||||||
robotInchesX = rotatedX * unitConversionFactor;
|
robotInchesX = rotatedX * unitConversionFactor;
|
||||||
@@ -99,7 +105,17 @@ public class Targeting {
|
|||||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||||
|
|
||||||
int remX = Math.floorMod((int) robotInchesX, tileSize);
|
int remX = Math.floorMod((int) robotInchesX, tileSize);
|
||||||
int remY = Math.floorMod((int) robotInchesX, tileSize);
|
int remY = Math.floorMod((int) robotInchesY, tileSize);
|
||||||
|
|
||||||
|
//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 {
|
||||||
|
// robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
|
// robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
|
//}
|
||||||
|
|
||||||
// Determine if we need to interpolate based on tile position.
|
// Determine if we need to interpolate based on tile position.
|
||||||
// if near upper or lower quarter or tile interpolate with next tile.
|
// if near upper or lower quarter or tile interpolate with next tile.
|
||||||
@@ -172,21 +188,11 @@ public class Targeting {
|
|||||||
interpolate = false;
|
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
|
// basic search
|
||||||
if (true) { //!interpolate) {
|
if (true) { //!interpolate) {
|
||||||
if ((robotGridY < 6) && (robotGridX < 6)) {
|
if ((robotGridY < 6) && (robotGridX < 6)) {
|
||||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
||||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle + ServoPositions.hoodOffset;
|
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
|
||||||
}
|
}
|
||||||
return recommendedSettings;
|
return recommendedSettings;
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -10,11 +10,11 @@ import com.qualcomm.hardware.limelightvision.LLResult;
|
|||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@@ -23,23 +23,21 @@ public class Turret {
|
|||||||
|
|
||||||
public static double turretTolerance = 0.02;
|
public static double turretTolerance = 0.02;
|
||||||
public static double turrPosScalar = 0.00011264432;
|
public static double turrPosScalar = 0.00011264432;
|
||||||
public static double turret180Range = 0.4;
|
public static double turret180Range = 0.54;
|
||||||
public static double turrDefault = 0.39;
|
public static double turrDefault = 0.35;
|
||||||
public static double turrMin = 0.15;
|
public static double turrMin = 0;
|
||||||
public static double turrMax = 0.85;
|
public static double turrMax = 1;
|
||||||
public static boolean limelightUsed = true;
|
public static boolean limelightUsed = true;
|
||||||
|
public static double limelightPosOffset = 5;
|
||||||
public static double manualOffset = 0.0;
|
public static double manualOffset = 0.0;
|
||||||
|
|
||||||
public static double visionCorrectionGain = 0.08; // Single tunable gain
|
// public static double visionCorrectionGain = 0.08; // Single tunable gain
|
||||||
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
// public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
||||||
public static double cameraBearingEqual = 0.5; // Deadband
|
// public static double cameraBearingEqual = 0.5; // Deadband
|
||||||
|
|
||||||
// TODO: tune these values for limelight
|
// public static double clampTolerance = 0.03;
|
||||||
|
|
||||||
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.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;
|
public static double B_PID_P = 0.08, B_PID_I = 0.0, B_PID_D = 0.007;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Limelight3A webcam;
|
Limelight3A webcam;
|
||||||
@@ -48,6 +46,8 @@ public class Turret {
|
|||||||
double limelightPosX = 0.0;
|
double limelightPosX = 0.0;
|
||||||
double limelightPosY = 0.0;
|
double limelightPosY = 0.0;
|
||||||
LLResult result;
|
LLResult result;
|
||||||
|
public static double TARGET_POSITION_TOLERANCE = 0.5;
|
||||||
|
public static double COLOR_OK_TOLERANCE = 2;
|
||||||
boolean bearingAligned = false;
|
boolean bearingAligned = false;
|
||||||
private boolean lockOffset = false;
|
private boolean lockOffset = false;
|
||||||
private int obeliskID = 0;
|
private int obeliskID = 0;
|
||||||
@@ -55,11 +55,12 @@ public class Turret {
|
|||||||
private double currentTrackOffset = 0.0;
|
private double currentTrackOffset = 0.0;
|
||||||
private double lightColor = Color.LightRed;
|
private double lightColor = Color.LightRed;
|
||||||
private int currentTrackCount = 0;
|
private int currentTrackCount = 0;
|
||||||
private double permanentOffset = 0.0;
|
double permanentOffset = 0.0;
|
||||||
private PIDController bearingPID;
|
private int prevPipeline = -1;
|
||||||
|
PIDController bearingPID;
|
||||||
|
|
||||||
private double prevTurretPos = 0.0;
|
public int llCoast = 0;
|
||||||
private boolean firstTurretPos = true;
|
public int LL_COAST_TICKS = 60;
|
||||||
|
|
||||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||||
this.TELE = tele;
|
this.TELE = tele;
|
||||||
@@ -81,21 +82,33 @@ public class Turret {
|
|||||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
||||||
|
|
||||||
}
|
}
|
||||||
private double prevTurrPos = 0.501;
|
private double prevTurrPos = 0;
|
||||||
|
private boolean isFirstTurretPos = true;
|
||||||
public void setTurret(double pos) {
|
public void setTurret(double pos) {
|
||||||
if (prevTurrPos != 0.501 && prevTurrPos != pos){
|
if (isFirstTurretPos || prevTurrPos != pos){
|
||||||
robot.turr1.setPosition(pos);
|
robot.turr1.setPosition(pos);
|
||||||
robot.turr2.setPosition(1-pos);
|
robot.turr2.setPosition(1-pos);
|
||||||
|
isFirstTurretPos = false;
|
||||||
}
|
}
|
||||||
prevTurrPos = pos;
|
prevTurrPos = pos;
|
||||||
}
|
}
|
||||||
|
public void pipelineSwitch(int pipeline){
|
||||||
|
if (prevPipeline != pipeline){
|
||||||
|
robot.limelight.pipelineSwitch(pipeline);
|
||||||
|
}
|
||||||
|
prevPipeline = pipeline;
|
||||||
|
}
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
public boolean turretEqual(double pos) {
|
||||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public static double alphaPosConstant = 0.3;
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
private void limelightRead() { // only for tracking purposes, not general reads
|
||||||
|
Double xPos = null;
|
||||||
|
Double yPos = null;
|
||||||
|
Double zPos = null;
|
||||||
|
Double hPos = null;
|
||||||
result = webcam.getLatestResult();
|
result = webcam.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
@@ -107,9 +120,27 @@ public class Turret {
|
|||||||
limelightPosX = botpose.getPosition().x;
|
limelightPosX = botpose.getPosition().x;
|
||||||
limelightPosY = botpose.getPosition().y;
|
limelightPosY = botpose.getPosition().y;
|
||||||
}
|
}
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
limelightTagPose = fiducial.getRobotPoseTargetSpace();
|
||||||
|
if (limelightTagPose != null){
|
||||||
|
xPos = limelightTagPose.getPosition().x;
|
||||||
|
yPos = limelightTagPose.getPosition().y;
|
||||||
|
zPos = limelightTagPose.getPosition().z;
|
||||||
|
hPos = limelightTagPose.getOrientation().getYaw();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (xPos != null){
|
||||||
|
if (zPos<0) {
|
||||||
|
limelightTagX = (alphaPosConstant * xPos) + ((1 - alphaPosConstant) * limelightTagX);
|
||||||
|
limelightTagY = (alphaPosConstant * yPos) + ((1 - alphaPosConstant) * limelightTagY);
|
||||||
|
limelightTagZ = (alphaPosConstant * zPos) + ((1 - alphaPosConstant) * limelightTagZ);
|
||||||
|
limelightTagH = (alphaPosConstant * hPos) + ((1 - alphaPosConstant) * limelightTagH);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getBearing() {
|
public double getBearing() {
|
||||||
@@ -122,12 +153,21 @@ public class Turret {
|
|||||||
return ty;
|
return ty;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Pose3D limelightTagPose;
|
||||||
|
double limelightTagX = 0.0;
|
||||||
|
double limelightTagY = 0.0;
|
||||||
|
double limelightTagZ = 0.0;
|
||||||
|
double limelightTagH = 0.0;
|
||||||
public double getLimelightX() {
|
public double getLimelightX() {
|
||||||
return limelightPosX;
|
return limelightTagX;
|
||||||
}
|
}
|
||||||
|
public double getLimelightY() {return limelightTagY;}
|
||||||
|
public double getLimelightZ(){return limelightTagZ;}
|
||||||
|
public double getLimelightH(){return limelightTagH;}
|
||||||
|
|
||||||
public double getLimelightY() {
|
public void relocalize(){
|
||||||
return limelightPosY;
|
setTurret(turrDefault);
|
||||||
|
limelightRead();
|
||||||
}
|
}
|
||||||
|
|
||||||
public int detectObelisk() {
|
public int detectObelisk() {
|
||||||
@@ -135,8 +175,12 @@ public class Turret {
|
|||||||
LLResult result = webcam.getLatestResult();
|
LLResult result = webcam.getLatestResult();
|
||||||
if (result != null && result.isValid()) {
|
if (result != null && result.isValid()) {
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
double prevTx = -1000;
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
obeliskID = fiducial.getFiducialId();
|
double currentTx = fiducial.getTargetXDegrees();
|
||||||
|
if (currentTx > prevTx){
|
||||||
|
obeliskID = fiducial.getFiducialId();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return obeliskID;
|
return obeliskID;
|
||||||
@@ -157,16 +201,16 @@ public class Turret {
|
|||||||
/*
|
/*
|
||||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||||
*/
|
*/
|
||||||
|
private double targetTx = 0;
|
||||||
|
public static double alphaTX = 0.5;
|
||||||
private double bearingAlign(LLResult llResult) {
|
private double bearingAlign(LLResult llResult) {
|
||||||
double bearingOffset = 0.0;
|
double bearingOffset = 0.0;
|
||||||
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
|
double tx = llResult.getTx(); // How far left or right the target is (degrees)
|
||||||
final double MIN_OFFSET_POWER = 0.15;
|
targetTx = (tx*alphaTX)+(targetTx*(1-alphaTX));
|
||||||
final double TARGET_POSITION_TOLERANCE = 1.0;
|
// final double MIN_OFFSET_POWER = 0.15;
|
||||||
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
// // 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 HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
||||||
final double DRIVE_POWER_REDUCTION = 2.0;
|
// final double DRIVE_POWER_REDUCTION = 2.0;
|
||||||
final double COLOR_OK_TOLERANCE = 2.5;
|
|
||||||
|
|
||||||
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
||||||
bearingAligned = true;
|
bearingAligned = true;
|
||||||
@@ -230,11 +274,18 @@ public class Turret {
|
|||||||
|
|
||||||
turretAngleDeg += permanentOffset;
|
turretAngleDeg += permanentOffset;
|
||||||
|
|
||||||
|
|
||||||
limelightRead();
|
limelightRead();
|
||||||
// Active correction if we see the target
|
// Active correction if we see the target
|
||||||
if (result.isValid() && !lockOffset && limelightUsed) {
|
if (result.isValid() && !lockOffset && limelightUsed) {
|
||||||
currentTrackOffset += bearingAlign(result);
|
currentTrackOffset += bearingAlign(result);
|
||||||
currentTrackCount++;
|
currentTrackCount++;
|
||||||
|
|
||||||
|
TELE.addData("LL Tracking: ", llCoast);
|
||||||
|
|
||||||
|
// Assume the last tracked value is always better than
|
||||||
|
// any previous value, even if its not fully aligned.
|
||||||
|
llCoast = LL_COAST_TICKS;
|
||||||
// double bearingError = Math.abs(tagBearingDeg);
|
// double bearingError = Math.abs(tagBearingDeg);
|
||||||
//
|
//
|
||||||
// if (bearingError > cameraBearingEqual) {
|
// if (bearingError > cameraBearingEqual) {
|
||||||
@@ -265,9 +316,15 @@ public class Turret {
|
|||||||
// if (currentTrackCount > 20) {
|
// if (currentTrackCount > 20) {
|
||||||
// offset = currentTrackOffset;
|
// offset = currentTrackOffset;
|
||||||
// }
|
// }
|
||||||
lightColor = Color.LightRed;
|
if (llCoast <= 0) {
|
||||||
currentTrackOffset = 0.0;
|
TELE.addData("LL No Track: ", llCoast);
|
||||||
currentTrackCount = 0;
|
lightColor = Color.LightRed;
|
||||||
|
currentTrackOffset = 0.0;
|
||||||
|
currentTrackCount = 0;
|
||||||
|
} else {
|
||||||
|
TELE.addData("LL Coasting: ", llCoast);
|
||||||
|
llCoast--;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Apply accumulated offset
|
// Apply accumulated offset
|
||||||
@@ -282,7 +339,7 @@ public class Turret {
|
|||||||
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
|
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
|
||||||
|
|
||||||
// Interpolate towards target position
|
// Interpolate towards target position
|
||||||
double currentPos = getTurrPos();
|
// double currentPos = getTurrPos();
|
||||||
double turretPos = targetTurretPos;
|
double turretPos = targetTurretPos;
|
||||||
|
|
||||||
if (targetTurretPos == turrMin) {
|
if (targetTurretPos == turrMin) {
|
||||||
@@ -292,7 +349,9 @@ public class Turret {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Set servo positions
|
// Set servo positions
|
||||||
setTurret(turretPos + manualOffset);
|
if (!Spindexer.whileShooting || abs(targetTx) > COLOR_OK_TOLERANCE){
|
||||||
|
setTurret(turretPos + manualOffset);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- TELEMETRY ---------------- */
|
/* ---------------- TELEMETRY ---------------- */
|
||||||
|
|||||||
@@ -6,7 +6,6 @@ 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 {
|
||||||
@@ -25,8 +24,6 @@ dependencies {
|
|||||||
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
||||||
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC
|
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC
|
||||||
|
|||||||
Reference in New Issue
Block a user