44 Commits

Author SHA1 Message Date
97e0183fdd Last commit of 23344... 2026-06-12 22:52:51 -04:00
ef6b0bebbb cowtown end 2026-06-11 15:55:56 -05:00
e8f80ef39e match 69 2026-06-10 10:43:02 -05:00
20137025c1 nighttime sleepy 2026-06-09 22:48:11 -05:00
12f433a221 day 1 2026-06-09 17:44:13 -05:00
1cd14021dd calibration 2026-06-09 09:29:32 -05:00
d0ee294d26 night before 2026-06-08 22:29:36 -05:00
b2a1ea32d9 a lot of changes happened 2026-06-08 15:29:22 -05:00
855dac7122 teleop tweaks 2026-06-07 23:48:26 -05:00
4cd890cef8 gate cycle auto good 2026-06-07 23:24:35 -05:00
9d03e1125a a lot of stuff happened 2026-06-07 21:19:00 -05:00
104058bbce copied changes from Mr. Kruger's commit 2026-06-07 15:06:54 -05:00
a9b57fd792 new autos 2026-06-06 23:15:26 -05:00
b09ba449b1 new autos 2026-06-06 23:14:06 -05:00
49a9e380d7 small changes 2026-06-06 21:52:04 -05:00
12cabd40db gate auto 2026-06-06 20:56:04 -05:00
351cff99ec oops 2026-06-06 20:53:40 -05:00
47ef898127 a lot of changes 2026-06-06 19:35:13 -05:00
d1626b20da fixed issues 2026-06-06 13:12:05 -05:00
e065084964 tele pose transfer 2026-06-05 18:51:54 -05:00
c36cac12f2 sorting auto is done 2026-06-05 18:25:12 -05:00
f7a9f6aaf5 small tweaks: added current pose telemetry and reduced coasting from limelight track 2026-06-05 14:29:21 -05:00
cc38b98d6f small tweaks: added loop times measurement 2026-06-05 14:19:39 -05:00
755d74a829 small tweaks: added loop times measurement and simplified SortedSpindexerTest 2026-06-05 14:18:47 -05:00
9d29e0b56c tweaks were made and hardware changes are needed 2026-06-04 22:13:49 -05:00
e25b372eca added limelight 2026-06-04 20:57:19 -05:00
3ab905af0c added limelight 2026-06-04 20:38:53 -05:00
58c11f5241 removed bunch of things to remove dash cluter 2026-06-04 20:38:45 -05:00
3afab333ef added delay based on ticks 2026-06-04 19:51:57 -05:00
9b92a59a75 Sorting beta workish 2026-06-04 18:47:23 -05:00
cca86f3691 Added transfer stuff 2026-06-04 18:13:14 -05:00
8c2a655c5c Merge remote-tracking branch 'origin/cowtown-work' into add-sorted-spindexer
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utilsv2/SpindexerTransferIntake.java
2026-06-04 18:12:04 -05:00
9a4aca90ba Added sorted modes and shoot 2026-06-04 18:10:31 -05:00
a3479d8816 hello iwnvvtw 2026-06-04 18:08:18 -05:00
e9b9ffc3b8 added transfer power manual command 2026-06-04 17:40:49 -05:00
e7056812b4 shooting is ok but NOT PERFECT 2026-06-04 17:29:14 -05:00
c15b9d58d4 teleop almost there 2026-06-04 16:06:27 -05:00
deefa19be4 added regression 2026-06-04 15:18:08 -05:00
3ae976c16d Merge remote-tracking branch 'origin/add-tilt' into cowtown-work 2026-06-03 15:51:51 -05:00
05f59d1820 Yay 2026-06-03 15:51:03 -05:00
128826f4fd Added tilt thing 2026-06-03 15:26:48 -05:00
a89535830b Lots o changes basically works ig 2026-06-03 15:05:29 -05:00
209c34b3fd Merge remote-tracking branch 'origin/danielv5' into update-teleop
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/NewShooterTest.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utilsv2/Shooter.java
2026-06-03 14:12:26 -05:00
d8cf594828 Fix some intrinsic bugs, refactor constructor in shooter 2026-06-03 14:08:49 -05:00
39 changed files with 3093 additions and 415 deletions

View File

@@ -1,3 +1,5 @@
Farewell, this is the last commit for the team 23344...to any who may use this repository, please feel free to contact us (keshavanandofficial@gmail.com), and we hope our code is of use to you and your team.
## NOTICE ## NOTICE
This repository contains the public FTC SDK for the DECODE (2025-2026) competition season. This repository contains the public FTC SDK for the DECODE (2025-2026) competition season.

View File

@@ -32,8 +32,6 @@ import org.firstinspires.ftc.teamcode.utilsv2.Turret;
import java.util.List; import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto12BallPedroPathing extends LinearOpMode { public class Auto12BallPedroPathing extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;
@@ -337,6 +335,8 @@ public class Auto12BallPedroPathing extends LinearOpMode {
initializePoses(); initializePoses();
follower.setPose(startPose); follower.setPose(startPose);
buildPaths(); buildPaths();
// turret.switchPipeline(Turret.PipelineMode.OBELISK);
robot.limelight.start();
sleep(2000); sleep(2000);
// turret.setTurret(turrDefault); // turret.setTurret(turrDefault);

View File

@@ -1,9 +1,6 @@
package org.firstinspires.ftc.teamcode.autonomous; package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed; import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -18,11 +15,12 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color; import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel; import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.tests.NewShooterTest;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes; import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
import java.util.List; import java.util.List;
@@ -33,66 +31,84 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
MultipleTelemetry TELE; MultipleTelemetry TELE;
Follower follower; Follower follower;
MeasuringLoopTimes loopTimes; MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
// Wait Times // Wait Times
public static double shootTime = 2; public static double sortedShootTime = 2.6;
public static double openGateTime = 1.5; public static double rapidWaitTime = 0.5;
public static double rapidShootTime = 0.8;
public static double openGateTime = 2.5;
public static double pushTime = 2;
// Extra Variables // Extra Variables
public static double intakePower = 0.3; public static double intakePower = 0.5;
double shootX, shootY, shootH; double shootX, shootY, shootH;
// Initialize path state machine // Initialize path state machine
private enum PathState { private enum PathState {
PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0, PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0,
PICKUP1, DRIVE_OPENGATE, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1, PICKUP1, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1,
DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2, DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2,
DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3 DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3
} }
PathState pathState = PathState.PUSHBOT; PathState pathState = PathState.PUSHBOT;
// Poses // Poses
public static double startPoseX = 84, startPoseY = 7, startPoseH = 90; public static double startPoseX = 12, startPoseY = -64, startPoseH = 90;
public static double pushBotX = 94, pushBotY = 9, pushBotH = 100; public static double pushBotX = 19, pushBotY = -63, pushBotH = 100;
public static double shoot0ControlX = 88.29667812142038, shoot0ControlY = 52.03493699885454; public static double shoot0ControlX = 16.29667812142038, shoot0ControlY = -19.67493699885454;
public static double shoot0X = 91, shoot0Y = 80, shoot0H = 0; public static double shoot0X = 19, shoot0Y = 10, shoot0H = 0;
public static double pickup1ControlX = 109.29381443298968, pickup1ControlY = 82.70618556701031; public static double pickup1X = 54, pickup1Y = 10, pickup1H = 0;
public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0; public static double openGateControlX = 37.184421534937, openGateControlY = 2.24455899198165;
public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165; public static double openGateX = 59, openGateY = 2, openGateH = 0;
public static double openGateX = 129, openGateY = 74, openGateH = 0; public static double shoot1ControlX = 40, shoot1ControlY = 3;
public static double shoot1ControlX = 112, shoot1ControlY = 75; public static double shoot1X = 19, shoot1Y = 10, shoot1H = 0;
public static double shoot1X = 91, shoot1Y = 80, shoot1H = -12; public static double drivePickup2X = 26, drivePickup2Y = -14, drivePickup2H = 0;
public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0; public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0;
public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0; public static double shoot2ControlX = 30, shoot2ControlY = -9;
public static double shoot2ControlX = 102, shoot2ControlY = 63; public static double shoot2X = 19, shoot2Y = 10, shoot2H = 0;
public static double shoot2X = 91, shoot2Y = 80, shoot2H = -50; public static double drivePickup3X = 26, drivePickup3Y = -37.5, drivePickup3H = 0;
public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0; public static double pickup3X = 61, pickup3Y = -37.5, pickup3H = 0;
public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0; public static double shoot3ControlX = 25.62371134020621, shoot3ControlY = -38.813287514318446;
public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446; public static double shoot3X = 12, shoot3Y = 40, shoot3H = -90;
public static double shoot3X = 84, shoot3Y = 105, shoot3H = -80; double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
double[] yPoses = {startPoseY, pushBotY, shoot0ControlY, shoot0Y,
pickup1Y, openGateControlY, openGateY, shoot1ControlY, shoot1Y,
drivePickup2Y, pickup2Y, shoot2ControlY, shoot2Y,
drivePickup3Y, pickup3Y, shoot3ControlY, shoot3Y};
double[] headings = {startPoseH, pushBotH, 0, shoot0H,
pickup1H, 0, openGateH, 0, shoot1H,
drivePickup2H, pickup2H, 0, shoot2H,
drivePickup3H, pickup3H, 0, shoot3H};
Pose startPose, pushBot, shoot0Control, shoot0, Pose startPose, pushBot, shoot0Control, shoot0,
pickup1Control, pickup1, openGateControl, openGate, shoot1Control, shoot1, pickup1, openGateControl, openGate, shoot1Control, shoot1,
drivePickup2, pickup2, shoot2Control, shoot2, drivePickup2, pickup2, shoot2Control, shoot2,
drivePickup3, pickup3, shoot3Control, shoot3; drivePickup3, pickup3, shoot3Control, shoot3;
private void initializePoses(){ private void initializePoses(){
startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH)); startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH)); pushBot = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1]));
shoot0Control = new Pose(shoot0ControlX, shoot0ControlY); shoot0Control = new Pose(xPoses[2], yPoses[2]);
shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H)); shoot0 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
pickup1Control = new Pose(pickup1ControlX, pickup1ControlY); pickup1 = new Pose(xPoses[4], yPoses[4], Math.toRadians(headings[4]));
pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H)); openGateControl = new Pose(xPoses[5], yPoses[5]);
openGateControl = new Pose(openGateControlX, openGateControlY); openGate = new Pose(xPoses[6], yPoses[6], Math.toRadians(headings[6]));
openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH)); shoot1Control = new Pose(xPoses[7], yPoses[7]);
shoot1Control = new Pose(shoot1ControlX, shoot1ControlY); shoot1 = new Pose(xPoses[8], yPoses[8], Math.toRadians(headings[8]));
shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H)); drivePickup2 = new Pose(xPoses[9], yPoses[9], Math.toRadians(headings[9]));
drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H)); pickup2 = new Pose(xPoses[10], yPoses[10], Math.toRadians(headings[10]));
pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H)); shoot2Control = new Pose(xPoses[11], yPoses[11]);
shoot2Control = new Pose(shoot2ControlX, shoot2ControlY); shoot2 = new Pose(xPoses[12], yPoses[12], Math.toRadians(headings[12]));
shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H)); drivePickup3 = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H)); pickup3 = new Pose(xPoses[14], yPoses[14], Math.toRadians(headings[14]));
pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H)); shoot3Control = new Pose(xPoses[15], yPoses[15]);
shoot3Control = new Pose(shoot3ControlX, shoot3ControlY); shoot3 = new Pose(xPoses[16], yPoses[16], Math.toRadians(headings[16]));
shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H));
} }
//Building Paths //Building Paths
@@ -112,7 +128,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
.build(); .build();
shoot0_pickup1 = follower.pathBuilder() shoot0_pickup1 = follower.pathBuilder()
.addPath(new BezierCurve(shoot0, pickup1Control, pickup1)) .addPath(new BezierLine(shoot0, pickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading()) .setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
.build(); .build();
@@ -164,46 +180,54 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
double currentTime = (double) System.currentTimeMillis() / 1000; double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){ switch(pathState){
case PUSHBOT: case PUSHBOT:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2400);
robot.setHoodPos(0.64);
if (startAuto){ if (startAuto){
follower.followPath(startPose_pushBot, true); follower.followPath(startPose_pushBot, false);
startAuto = false; startAuto = false;
timeStamp = currentTime;
shootX = shoot0X; shootX = shoot0X;
shootY = shoot0Y; shootY = shoot0Y;
shootH = shoot0H; shootH = shoot0H;
} }
if (!follower.isBusy()){ if (!follower.isBusy() || currentTime - timeStamp > pushTime){
follower.followPath(pushBot_shoot0, true); follower.followPath(pushBot_shoot0, true);
pathState = PathState.DRIVE_SHOOT0; pathState = PathState.DRIVE_SHOOT0;
} }
break; break;
case DRIVE_SHOOT0: case DRIVE_SHOOT0:
if (!follower.isBusy()){ if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime; timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0; pathState = PathState.WAIT_SHOOT0;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
} }
break; break;
case WAIT_SHOOT0: case WAIT_SHOOT0:
if (currentTime - timeStamp > shootTime){ if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot0_pickup1, intakePower, false); follower.followPath(shoot0_pickup1, intakePower, false);
pathState = PathState.PICKUP1; pathState = PathState.PICKUP1;
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SORTED);
} }
break; break;
case PICKUP1: case PICKUP1:
if (!follower.isBusy()){ if (!follower.isBusy()){
follower.followPath(pickup1_openGate, true); follower.followPath(pickup1_openGate, false);
pathState = PathState.OPENGATE; pathState = PathState.OPENGATE;
shootX = shoot1X; shootX = shoot1X;
shootY = shoot1Y; shootY = shoot1Y;
shootH = shoot1H; shootH = shoot1H;
}
break;
case DRIVE_OPENGATE:
if (!follower.isBusy()){
pathState = PathState.OPENGATE;
timeStamp = currentTime; timeStamp = currentTime;
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
} }
break; break;
case OPENGATE: case OPENGATE:
robot.setIntakePower(0);
if (currentTime - timeStamp > openGateTime){ if (currentTime - timeStamp > openGateTime){
follower.followPath(openGate_shoot1, true); follower.followPath(openGate_shoot1, true);
pathState = PathState.DRIVE_SHOOT1; pathState = PathState.DRIVE_SHOOT1;
@@ -213,10 +237,11 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (!follower.isBusy()){ if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT1; pathState = PathState.WAIT_SHOOT1;
timeStamp = currentTime; timeStamp = currentTime;
spindexer.startSortedShoot();
} }
break; break;
case WAIT_SHOOT1: case WAIT_SHOOT1:
if (currentTime - timeStamp > shootTime){ if (currentTime - timeStamp > sortedShootTime){
follower.followPath(shoot1_drivePickup2, true); follower.followPath(shoot1_drivePickup2, true);
pathState = PathState.DRIVE_PICKUP2; pathState = PathState.DRIVE_PICKUP2;
} }
@@ -240,16 +265,19 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (!follower.isBusy()){ if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT2; pathState = PathState.WAIT_SHOOT2;
timeStamp = currentTime; timeStamp = currentTime;
spindexer.startSortedShoot();
} }
break; break;
case WAIT_SHOOT2: case WAIT_SHOOT2:
if (currentTime - timeStamp > shootTime){ if (currentTime - timeStamp > sortedShootTime){
follower.followPath(shoot2_drivePickup3, true); follower.followPath(shoot2_drivePickup3, true);
pathState = PathState.DRIVE_PICKUP3; pathState = PathState.DRIVE_PICKUP3;
} }
break; break;
case DRIVE_PICKUP3: case DRIVE_PICKUP3:
if (!follower.isBusy()){ if (!follower.isBusy()){
shooter.setFlywheelVelocity(2250);
robot.setHoodPos(0.75);
follower.followPath(drivePickup3_pickup3, intakePower, false); follower.followPath(drivePickup3_pickup3, intakePower, false);
pathState = PathState.PICKUP3; pathState = PathState.PICKUP3;
} }
@@ -266,10 +294,11 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
case DRIVE_SHOOT3: case DRIVE_SHOOT3:
if (!follower.isBusy()){ if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT3; pathState = PathState.WAIT_SHOOT3;
spindexer.startSortedShoot();
} }
break; break;
case WAIT_SHOOT3: case WAIT_SHOOT3:
// add line here to say "done auto' // add line here to say "done auto"
break; break;
default: default:
break; break;
@@ -278,7 +307,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
} }
// Used for changing alliance // Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return (144-pose);} private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){ private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading; heading = 180 - heading;
while (heading > 180) {heading-=360;} while (heading > 180) {heading-=360;}
@@ -296,30 +325,39 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
} }
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap); follower = Constants.createFollower(hardwareMap);
follower.setStartingPose(new Pose(72,72,0)); sleep(1000);
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes(); loopTimes = new MeasuringLoopTimes();
loopTimes.init(); loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean initializeRobot = false; boolean initializeRobot = false;
while (opModeInInit()){ while (opModeInInit()){
follower.update(); follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
}
if (gamepad1.crossWasPressed() && !initializeRobot){ if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance; Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X, if (!initializeRobot){
pickup1ControlX, pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X, if ((Color.redAlliance && xPoses[0] < 0)
drivePickup2X, pickup2X, shoot2ControlX, shoot2X, || (!Color.redAlliance && xPoses[0] > 0)){
drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
double[] headings = {startPoseH, pushBotH, shoot0H,
pickup1H, openGateH, shoot1H,
drivePickup2H, pickup2H, shoot2H,
drivePickup3H, pickup3H, shoot3H};
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);} for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);} for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
} }
}
if (gamepad1.triangleWasPressed()){ if (gamepad1.triangleWasPressed()){
initializeRobot = true; initializeRobot = true;
@@ -327,11 +365,27 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
follower.setPose(startPose); follower.setPose(startPose);
buildPaths(); buildPaths();
sleep(2000); sleep(2000);
turret.switchPipeline(Turret.PipelineMode.OBELISK);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
NewShooterTest.transferPower = -0.8;
if (initializeRobot){
//add obelisk read here
shooter.setState(Shooter.ShooterState.READ_OBELISK);
int ID = turret.getObeliskID();
spindexer.setDesiredPatternAuto(ID);
TELE.addData("ID", ID);
shooter.update(robot.voltage.getVoltage());
} }
TELE.addData("Red Alliance?", Color.redAlliance); TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot); TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose()); TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update(); TELE.update();
} }
@@ -339,15 +393,19 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (isStopRequested()) return; if (isStopRequested()) return;
limelightUsed = false;
while (opModeIsActive()){ while (opModeIsActive()){
park.unpark();
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update(); follower.update();
}
pathStateMachine(); pathStateMachine();
Pose currentPose = follower.getPose(); TeleopV4.teleStart = follower.getPose();
teleStartPoseX = currentPose.getX();
teleStartPoseY = currentPose.getY(); spindexer.update();
teleStartPoseH = Math.toDegrees(currentPose.getHeading());
for (LynxModule hub : allHubs) { for (LynxModule hub : allHubs) {
hub.clearBulkCache(); hub.clearBulkCache();
@@ -357,9 +415,9 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
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("X:", currentPose.getX()); TELE.addData("X:", TeleopV4.teleStart.getX());
TELE.addData("Y:", currentPose.getY()); TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", currentPose.getHeading()); TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update(); TELE.update();
} }
} }

View File

@@ -0,0 +1,356 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.PathChain;
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.tests.NewShooterTest;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto15Ball_Back extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
// Wait Times
public static double rapidWaitTime = 0.7;
public static double rapidShootTime = 2.6;
public static double loadPickupTime = 3;
// Initialize path state machine
private enum PathState {
WAIT_VELOCITY, WAIT_SHOOT0,
PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3,
PICKUP_LOAD, DRIVE_SHOOT_LOAD, WAIT_SHOOT_LOAD,
INTAKE_GATE, DRIVE_SHOOT_GATE, WAIT_SHOOT_GATE, LEAVE
}
PathState pathState = PathState.WAIT_VELOCITY;
// Poses
public static double startPoseX = 16, startPoseY = -64, startPoseH = 90;
public static double pickup3ControlX = 12, pickup3ControlY = -37;
public static double pickup3X = 61, pickup3Y = -37, pickup3H = 0;
public static double shoot3X = 16, shoot3Y = -55, shoot3H = 0;
public static double pickupLoadControlX = 21.23654066437572, pickupLoadControlY = -62.311626575028637;
public static double pickupLoadX = 63, pickupLoadY = -63, pickupLoadH = 0;
public static double shootLoadControlX = 21.23654066437572, shootLoadControlY = -62.311626575028637;
public static double shootLoadX = 16, shootLoadY = -55, shootLoadH = 0;
public static double intakeGateControl1X = 51.9656357388316, intakeGateControl1Y = -65.506277205040073;
public static double intakeGateControl2X = 60.13459335624285, intakeGateControl2Y = -67.300458190148911;
public static double intakeGateX = 63, intakeGateY = -35, intakeGateH = 90;
public static double shootGateControlX = 53.8705612829324, shootGateControlY = -35.14501718213059;
public static double shootGateX = 16, shootGateY = -55, shootGateH = 0;
public static double leaveX = 36, leaveY = -58, leaveH = 0;
double[] xPoses = {startPoseX, pickup3ControlX, pickup3X, shoot3X,
pickupLoadControlX, pickupLoadX, shootLoadControlX, shootLoadX,
intakeGateControl1X, intakeGateControl2X, intakeGateX, shootGateControlX, shootGateX, leaveX};
double[] yPoses = {startPoseY, pickup3ControlY, pickup3Y, shoot3Y,
pickupLoadControlY, pickupLoadY, shootLoadControlY, shootLoadY,
intakeGateControl1Y, intakeGateControl2Y, intakeGateY, shootGateControlY, shootGateY, leaveY};
double[] headings = {startPoseH, 0, pickup3H, shoot3H,
0, pickupLoadH, 0, shootLoadH,
0, 0, intakeGateH, 0, shootGateH, leaveH};
Pose startPose, pickup3Control, pickup3, shoot3,
pickupLoadControl, pickupLoad, shootLoadControl, shootLoad,
intakeGateControl1, intakeGateControl2, intakeGate, shootGateControl, shootGate, leave;
private void initializePoses(){
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
pickup3Control = new Pose(xPoses[1], yPoses[1]);
pickup3 = new Pose(xPoses[2], yPoses[2], Math.toRadians(headings[2]));
shoot3 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
pickupLoadControl = new Pose(xPoses[4], yPoses[4]);
pickupLoad = new Pose(xPoses[5], yPoses[5], Math.toRadians(headings[5]));
shootLoadControl = new Pose(xPoses[6], yPoses[6]);
shootLoad = new Pose(xPoses[7], yPoses[7], Math.toRadians(headings[7]));
intakeGateControl1 = new Pose(xPoses[8], yPoses[8]);
intakeGateControl2 = new Pose(xPoses[9], yPoses[9]);
intakeGate = new Pose(xPoses[10], yPoses[10], Math.toRadians(headings[10]));
shootGateControl = new Pose(xPoses[11], yPoses[11]);
shootGate = new Pose(xPoses[12], yPoses[12], Math.toRadians(headings[12]));
leave = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
}
//Building Paths
PathChain startPose_pickup3, pickup3_shoot3, shoot3_pickupLoad, pickupLoad_shootLoad,
shootLoad_intakeGate, intakeGate_shootGate, shootGate_intakeGate, shootGate_leave;
private void buildPaths(){
startPose_pickup3 = follower.pathBuilder()
.addPath(new BezierCurve(startPose, pickup3Control, pickup3))
.setTangentHeadingInterpolation()
.build();
pickup3_shoot3 = follower.pathBuilder()
.addPath(new BezierLine(pickup3, shoot3))
.setLinearHeadingInterpolation(pickup3.getHeading(), shoot3.getHeading())
.build();
shoot3_pickupLoad = follower.pathBuilder()
.addPath(new BezierCurve(shoot3, pickupLoadControl, pickupLoad))
.setLinearHeadingInterpolation(shoot3.getHeading(), pickupLoad.getHeading())
.build();
pickupLoad_shootLoad = follower.pathBuilder()
.addPath(new BezierCurve(pickupLoad, shootLoadControl, shootLoad))
.setLinearHeadingInterpolation(pickupLoad.getHeading(), shootLoad.getHeading())
.build();
shootLoad_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shootLoad, intakeGateControl1, intakeGateControl2, intakeGate))
.setTangentHeadingInterpolation()
.build();
intakeGate_shootGate = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, shootGateControl, shootGate))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootGate.getHeading())
.build();
shootGate_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shootGate, intakeGateControl1, intakeGateControl2, intakeGate))
.setTangentHeadingInterpolation()
.build();
shootGate_leave = follower.pathBuilder()
.addPath(new BezierLine(shootGate, leave))
.setLinearHeadingInterpolation(shootGate.getHeading(), leave.getHeading())
.build();
}
//Path State Machine
private int startAuto = 0;
private double timeStamp = 0;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case WAIT_VELOCITY:
shooter.setFlywheelVelocity(3250);
robot.setHoodPos(0.65);
if (flywheel.getSteady()){
startAuto++;
}
if (startAuto > 6){
spindexer.startBackShooting();
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
}
timeStamp = currentTime;
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > rapidShootTime){
follower.followPath(startPose_pickup3, false);
pathState = PathState.PICKUP3;
}
break;
case PICKUP3:
if (!follower.isBusy()){
follower.followPath(pickup3_shoot3, true);
pathState = PathState.DRIVE_SHOOT3;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT3:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT3;
spindexer.startBackShooting();
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT3:
if (currentTime - timeStamp > rapidShootTime){
follower.followPath(shoot3_pickupLoad, false);
pathState = PathState.PICKUP_LOAD;
timeStamp = currentTime;
}
break;
case PICKUP_LOAD:
if (currentTime - timeStamp > loadPickupTime){
follower.followPath(pickupLoad_shootLoad, true);
pathState = PathState.DRIVE_SHOOT_LOAD;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT_LOAD:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_LOAD;
spindexer.startBackShooting();
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_LOAD:
if (currentTime - timeStamp > rapidShootTime){
follower.followPath(shootLoad_intakeGate, false);
pathState = PathState.INTAKE_GATE;
timeStamp = currentTime;
}
break;
case INTAKE_GATE:
if (!follower.isBusy()){
follower.followPath(intakeGate_shootGate, true);
pathState = PathState.DRIVE_SHOOT_GATE;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT_GATE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_GATE;
spindexer.startBackShooting();
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_GATE:
if (currentTime - timeStamp > rapidShootTime){
// follower.followPath(shootGate_intakeGate, false);
follower.followPath(shootGate_leave, true);
pathState = PathState.LEAVE;
timeStamp = currentTime;
}
break;
case LEAVE:
// add line here to say "done auto"
break;
default:
break;
}
TELE.update(); // use for debugging
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading;
while (heading > 180) {heading-=360;}
while (heading <= -180) {heading+=360;}
return heading;
}
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) {
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
}
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean initializeRobot = false;
while (opModeInInit()){
park.unpark();
follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Open);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Closed);
robot.setTurretPos(Turret.neutralPosition);
}
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
if (!initializeRobot){
if ((Color.redAlliance && xPoses[0] < 0)
|| (!Color.redAlliance && xPoses[0] > 0)){
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
NewShooterTest.transferPower = -0.6;
TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update();
}
pathStateMachine();
TeleopV4.teleStart = follower.getPose();
spindexer.update();
for (LynxModule hub : allHubs) {
hub.clearBulkCache();
}
loopTimes.loop();
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("X:", TeleopV4.teleStart.getX());
TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update();
}
}
}

View File

@@ -0,0 +1,478 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.PathChain;
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.tests.NewShooterTest;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto21Ball_Front_Gate extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
double runtime = 0;
// Wait Times
public static double rapidWaitTimeShoot0 = 0.2;
public static double rapidWaitTimeShoot1 = 0.2;
public static double rapidWaitTimeShoot2 = 0.2;
public static double rapidWaitTimeShootGate = 0.4;
public static double rapidShootTime = 0.4;
public static double openGate1Time = 1.8;
public static double openGate2Time = 1;
public static double openGateWaitTimeMax = 3;
public static int maxLoopCycles = 4;
// Initialize path state machine
private enum PathState {
DRIVE_SHOOT0, WAIT_SHOOT0,
PICKUP1, OPENGATE1, DRIVE_SHOOT1, WAIT_SHOOT1,
PICKUP2, OPENGATE2, DRIVE_SHOOT2, WAIT_SHOOT2,
INTAKE_GATE, DRIVE_SHOOT_GATE, WAIT_SHOOT_GATE, DRIVE_SHOOT_LEAVE, WAIT_SHOOT_LEAVE
}
PathState pathState = PathState.DRIVE_SHOOT0;
// Poses
public static double startPoseX = 55, startPoseY = 39, startPoseH = 0;
public static double shoot0X = 25, shoot0Y = 18, shoot0H = 0;
public static double pickup1ControlX = 29.53321878579611, pickup1ControlY = 9.84077892325314;
public static double pickup1X = 50, pickup1Y = 10, pickup1H = 0;
public static double openGate1ControlX = 43.82989690721648, openGate1ControlY = 3.86540664375714;
public static double openGate1X = 59, openGate1Y = 2, openGate1H = 0;
public static double shoot1ControlX = 40, shoot1ControlY = 3;
public static double shoot1X = 25, shoot1Y = 11, shoot1H = -30;
public static double pickup2ControlX = 18, pickup2ControlY = -18;
public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0;
public static double openGate2ControlX = 45.9782359679267, openGate2ControlY = -15.106643757159245;
public static double openGate2X = 57, openGate2Y = -8, openGate2H = 0;
public static double shoot2ControlX = 57, shoot2ControlY = -8;
public static double shoot2X = 16, shoot2Y = 4, shoot2H = -30;
public static double intakeGateControlX = 60, intakeGateControlY = -12;
public static double toGateX = 60, toGateY = -10;
public static double intakeGateX = 62, intakeGateY = -12, intakeGateH = 25;
public static double shootGateControlX = 40, shootGateControlY = -5;
public static double shootGateX = 16, shootGateY = 4, shootGateH = -30;
public static double shootLeaveControlX = 56, shootLeaveControlY = -10;
public static double shootLeaveX = 16, shootLeaveY = 36, shootLeaveH = -50;
public static double leaveX = 45, leaveY = 10, leaveH = 0;
public static double awayFromGateX = 40, awayFromGateY = -12, awayFromGateH = 0;
double[] xPoses = {startPoseX, shoot0X,
pickup1ControlX, pickup1X, openGate1ControlX, openGate1X, shoot1ControlX, shoot1X,
pickup2ControlX, pickup2X, openGate2ControlX, openGate2X, shoot2ControlX, shoot2X,
intakeGateControlX, intakeGateX, shootGateControlX, shootGateX,
shootLeaveControlX, shootLeaveX, leaveX, awayFromGateX, toGateX};
double[] yPoses = {startPoseY, shoot0Y,
pickup1ControlY, pickup1Y, openGate1ControlY, openGate1Y, shoot1ControlY, shoot1Y,
pickup2ControlY, pickup2Y, openGate2ControlY, openGate2Y, shoot2ControlY, shoot2Y,
intakeGateControlY, intakeGateY, shootGateControlY, shootGateY,
shootLeaveControlY, shootLeaveY, leaveY, awayFromGateY, toGateY};
double[] headings = {startPoseH, shoot0H,
0, pickup1H, 0, openGate1H, 0, shoot1H,
0, pickup2H, 0, openGate2H, 0, shoot2H,
0, intakeGateH, 0, shootGateH,
0, shootLeaveH, leaveH, awayFromGateH, 0};
Pose startPose, shoot0,
pickup1Control, pickup1, openGate1Control, openGate1, shoot1Control, shoot1,
pickup2Control, pickup2, openGate2Control, openGate2, shoot2Control, shoot2,
intakeGateControl, intakeGate, shootGateControl, shootGate,
shootLeaveControl, shootLeave, leave, awayFromGate, toGate;
private void initializePoses(){
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
shoot0 = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1]));
pickup1Control = new Pose(xPoses[2], yPoses[2]);
pickup1 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
openGate1Control = new Pose(xPoses[4], yPoses[4]);
openGate1 = new Pose(xPoses[5], yPoses[5], Math.toRadians(headings[5]));
shoot1Control = new Pose(xPoses[6], yPoses[6]);
shoot1 = new Pose(xPoses[7], yPoses[7], Math.toRadians(headings[7]));
pickup2Control = new Pose(xPoses[8], yPoses[8]);
pickup2 = new Pose(xPoses[9], yPoses[9], Math.toRadians(headings[9]));
openGate2Control = new Pose(xPoses[10], yPoses[10]);
openGate2 = new Pose(xPoses[11], yPoses[11], Math.toRadians(headings[11]));
shoot2Control = new Pose(xPoses[12], yPoses[12]);
shoot2 = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
intakeGateControl = new Pose(xPoses[14], yPoses[14]);
intakeGate = new Pose(xPoses[15], yPoses[15], Math.toRadians(headings[15]));
shootGateControl = new Pose(xPoses[16], yPoses[16]);
shootGate = new Pose(xPoses[17], yPoses[17], Math.toRadians(headings[17]));
shootLeaveControl = new Pose(xPoses[18], yPoses[18]);
shootLeave = new Pose(xPoses[19], yPoses[19], Math.toRadians(headings[19]));
leave = new Pose(xPoses[20], yPoses[20], Math.toRadians(headings[20]));
awayFromGate = new Pose(xPoses[21], yPoses[21], Math.toRadians(headings[21]));
toGate = new Pose(xPoses[22], yPoses[22]);
}
//Building Paths
PathChain startPose_shoot0, shoot0_pickup1, pickup1_openGate1, openGate1_shoot1,
shoot1_pickup2, pickup2_openGate2, openGate2_shoot2, shootGate_intakeGate,
shoot2_intakeGate, intakeGate_shootGate, intakeGate_shootLeave, shootGate_leave, intakeGate_awayFromGate;
private void buildPaths(){
startPose_shoot0 = follower.pathBuilder()
.addPath(new BezierLine(startPose, shoot0))
.setLinearHeadingInterpolation(startPose.getHeading(), shoot0.getHeading())
.build();
shoot0_pickup1 = follower.pathBuilder()
.addPath(new BezierCurve(shoot0, pickup1Control, pickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
.build();
pickup1_openGate1 = follower.pathBuilder()
.addPath(new BezierCurve(pickup1, openGate1Control, openGate1))
.setLinearHeadingInterpolation(pickup1.getHeading(), openGate1.getHeading())
.build();
openGate1_shoot1 = follower.pathBuilder()
.addPath(new BezierCurve(openGate1, shoot1Control, shoot1))
.setLinearHeadingInterpolation(openGate1.getHeading(), shoot1.getHeading())
.build();
shoot1_pickup2 = follower.pathBuilder()
.addPath(new BezierCurve(shoot1, pickup2Control, pickup2))
.setLinearHeadingInterpolation(shoot1.getHeading(), pickup2.getHeading())
.build();
pickup2_openGate2 = follower.pathBuilder()
.addPath(new BezierCurve(pickup2, openGate2Control, openGate2))
.setLinearHeadingInterpolation(pickup2.getHeading(), openGate2.getHeading())
.build();
openGate2_shoot2 = follower.pathBuilder()
.addPath(new BezierLine(openGate2, shoot2))
.setTangentHeadingInterpolation()
.setReversed()
.build();
shoot2_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shoot2, intakeGateControl, toGate))
.setLinearHeadingInterpolation(shoot2.getHeading(), intakeGate.getHeading())
.build();
intakeGate_shootGate = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, shootGateControl, shootGate))
.setTangentHeadingInterpolation()
.setReversed()
.build();
shootGate_intakeGate = follower.pathBuilder()
.addPath(new BezierLine(shootGate, intakeGate))
.setLinearHeadingInterpolation(shootGate.getHeading(), intakeGate.getHeading())
.build();
intakeGate_shootLeave = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, pickup2Control, shootLeave))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootLeave.getHeading())
.build();
shootGate_leave = follower.pathBuilder()
.addPath(new BezierLine(shootGate, leave))
.setLinearHeadingInterpolation(shootGate.getHeading(), leave.getHeading())
.build();
intakeGate_awayFromGate = follower.pathBuilder()
.addPath(new BezierLine(intakeGate, awayFromGate))
.setLinearHeadingInterpolation(intakeGate.getHeading(), awayFromGate.getHeading())
.build();
}
//Path State Machine
private boolean startAuto = true;
private double timeStamp = 0;
private int cycle = 0;
boolean toGateBool = false;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case DRIVE_SHOOT0:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
if (startAuto){
follower.followPath(startPose_shoot0, false);
startAuto = false;
}
if ((follower.atParametricEnd() || !follower.isBusy()) && currentTime - timeStamp > rapidWaitTimeShoot0){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy() && !follower.atParametricEnd()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot0_pickup1, false);
pathState = PathState.PICKUP1;
}
break;
case PICKUP1:
if (!follower.isBusy()){
follower.followPath(pickup1_openGate1, false);
pathState = PathState.OPENGATE1;
timeStamp = currentTime;
}
break;
case OPENGATE1:
if (currentTime - timeStamp > openGate1Time){
follower.followPath(openGate1_shoot1, false);
pathState = PathState.DRIVE_SHOOT1;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT1:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTimeShoot1){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT1;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT1:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot1_pickup2, false);
pathState = PathState.PICKUP2;
}
break;
case PICKUP2:
if (!follower.isBusy()){
shooter.setFlywheelVelocity(2500);
robot.setHoodPos(0.6);
follower.followPath(pickup2_openGate2, false);
pathState = PathState.OPENGATE2;
timeStamp = currentTime;
}
break;
case OPENGATE2:
if (currentTime - timeStamp > openGate2Time){
follower.followPath(openGate2_shoot2, false);
pathState = PathState.DRIVE_SHOOT2;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT2:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTimeShoot2){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT2;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT2:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot2_intakeGate, true);
pathState = PathState.INTAKE_GATE;
timeStamp = currentTime;
toGateBool = true;
}
break;
case INTAKE_GATE:
if ((currentTime - timeStamp > openGateWaitTimeMax)){
if (cycle == 0){
openGateWaitTimeMax = openGateWaitTimeMax + 0.75;
}
if (cycle >= maxLoopCycles - 1){
follower.followPath(intakeGate_shootLeave, true);
pathState = PathState.DRIVE_SHOOT_LEAVE;
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
} else {
follower.followPath(intakeGate_shootGate, false);
pathState = PathState.DRIVE_SHOOT_GATE;
}
timeStamp = currentTime;
}
// TODO: add logic to shoot gate
break;
case DRIVE_SHOOT_GATE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTimeShootGate){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_GATE;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_GATE:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
cycle++;
if (getRuntime() - runtime > 24 || cycle >= maxLoopCycles){
follower.followPath(shootGate_leave, true);
pathState = PathState.WAIT_SHOOT_LEAVE;
} else {
follower.followPath(shootGate_intakeGate, true);
pathState = PathState.INTAKE_GATE;
toGateBool = true;
}
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT_LEAVE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTimeShootGate){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_LEAVE;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_LEAVE:
// add line here to say "done auto"
break;
default:
break;
}
TELE.addData("Moving?", follower.isBusy());
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading;
while (heading > 180) {heading-=360;}
while (heading <= -180) {heading+=360;}
return heading;
}
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) {
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
}
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean startAuto = true;
boolean initializeRobot = false;
while (opModeInInit()){
follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
}
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
if (!initializeRobot){
if ((Color.redAlliance && xPoses[0] < 0)
|| (!Color.redAlliance && xPoses[0] > 0)){
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
NewShooterTest.transferPower = -0.8;
TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
if (startAuto){
runtime = getRuntime();
startAuto = false;
}
park.unpark();
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update();
}
pathStateMachine();
TeleopV4.teleStart = follower.getPose();
spindexer.update();
for (LynxModule hub : allHubs) {
hub.clearBulkCache();
}
loopTimes.loop();
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("X:", TeleopV4.teleStart.getX());
TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update();
}
}
}

View File

@@ -51,8 +51,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close extends LinearOpMode { public class Auto_LT_Close extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93; public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double velGate0Start = 2700, hoodGate0Start = 0.6; public static double velGate0Start = 2700, hoodGate0Start = 0.6;

View File

@@ -43,8 +43,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Far extends LinearOpMode { public class Auto_LT_Far extends LinearOpMode {
public static double shoot0Vel = 3300, shoot0Hood = 0.48; public static double shoot0Vel = 3300, shoot0Hood = 0.48;
double xLeave, yLeave, hLeave; double xLeave, yLeave, hLeave;

View File

@@ -37,7 +37,6 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.Objects; import java.util.Objects;
@Config
public class AutoActions { public class AutoActions {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;

View File

@@ -85,9 +85,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close_12Ball extends LinearOpMode { public class Auto_LT_Close_12Ball extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93; public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2; public static double autoSpinStartPos = 0.2;

View File

@@ -93,9 +93,7 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.Objects; import java.util.Objects;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close_GateOpen extends LinearOpMode { public class Auto_LT_Close_GateOpen extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93; public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2; public static double autoSpinStartPos = 0.2;

View File

@@ -82,9 +82,7 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos; import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.List; import java.util.List;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class ProtoAutoClose_V3 extends LinearOpMode { public class ProtoAutoClose_V3 extends LinearOpMode {
public static double intake1Time = 2.7; public static double intake1Time = 2.7;
public static double intake2Time = 3.0; public static double intake2Time = 3.0;

View File

@@ -5,7 +5,7 @@ import com.acmerobotics.dashboard.config.Config;
@Config @Config
public class ServoPositions { public class ServoPositions {
public static double rapidFireBlocker_Closed = 0.35; public static double rapidFireBlocker_Closed = 0.32;
public static double rapidFireBlocker_Open = 0.5; public static double rapidFireBlocker_Open = 0.5;
public static double spindexBlocker_Closed = 0.31; public static double spindexBlocker_Closed = 0.31;
@@ -16,6 +16,7 @@ public class ServoPositions {
public static double spindexer_A3 = 0.54; public static double spindexer_A3 = 0.54;
public static double spindexer_B1 = 0.73; public static double spindexer_B1 = 0.73;
public static double spindexer_B2 = 0.92; public static double spindexer_B2 = 0.92;
public static double spindexer_StopShooting = 0.44;
public static double spindexer_intakePos1 = 0.18; //0.13; public static double spindexer_intakePos1 = 0.18; //0.13;
@@ -34,9 +35,9 @@ public class ServoPositions {
public static double shootAllSpindexerSpeedIncrease = 0.01; public static double shootAllSpindexerSpeedIncrease = 0.01;
public static double transferServo_out = 0.57; public static double transferServo_out = 0.28;
public static double transferServo_in = 0.77; public static double transferServo_in = 0.52;
public static double hoodAuto = 0.27; public static double hoodAuto = 0.27;

View File

@@ -5,7 +5,7 @@ import com.pedropathing.control.FilteredPIDFCoefficients;
import com.pedropathing.control.PIDFCoefficients; import com.pedropathing.control.PIDFCoefficients;
import com.pedropathing.follower.Follower; import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants; import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.FollowerBuilder; import org.firstinspires.ftc.teamcode.pedroPathing.FollowerBuilder;
import com.pedropathing.ftc.drivetrains.MecanumConstants; import com.pedropathing.ftc.drivetrains.MecanumConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants; import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.paths.PathConstraints; import com.pedropathing.paths.PathConstraints;
@@ -22,7 +22,7 @@ public class Constants {
.lateralZeroPowerAcceleration(-60.876) .lateralZeroPowerAcceleration(-60.876)
.translationalPIDFCoefficients(new PIDFCoefficients(0.15, 0, 0.015, 0.02)) .translationalPIDFCoefficients(new PIDFCoefficients(0.15, 0, 0.015, 0.02))
.headingPIDFCoefficients(new PIDFCoefficients(1, 0, 0.02, 0.02)) .headingPIDFCoefficients(new PIDFCoefficients(1, 0, 0.02, 0.02))
.drivePIDFCoefficients(new FilteredPIDFCoefficients(0.02, 0, 0.00001, 0.6, 0.015)) .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.013, 0, 0.00001, 0.6, 0.015))
.centripetalScaling(0.0005); .centripetalScaling(0.0005);
public static MecanumConstants driveConstants = new MecanumConstants() public static MecanumConstants driveConstants = new MecanumConstants()
@@ -42,8 +42,8 @@ public class Constants {
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, breakingStrength, 1); public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, breakingStrength, 1);
public static PinpointConstants localizerConstants = new PinpointConstants() public static PinpointConstants localizerConstants = new PinpointConstants()
.forwardPodY(3.7795) .forwardPodY(-3.7795)
.strafePodX(-3.676) .strafePodX(-3.769)
.distanceUnit(DistanceUnit.INCH) .distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint") .hardwareMapName("pinpoint")
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
@@ -51,10 +51,16 @@ public class Constants {
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD); .strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD);
public static Follower createFollower(HardwareMap hardwareMap) { public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap) FollowerBuilder followerBuilder;
followerBuilder = new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints) .pathConstraints(pathConstraints)
.mecanumDrivetrain(driveConstants) .mecanumDrivetrain(driveConstants)
.pinpointLocalizer(localizerConstants) .pinpointLocalizer(localizerConstants);
.build();
followerBuilder.resetPinpoint();
followerBuilder.recalibrateIMU();
return followerBuilder.build();
} }
} }

View File

@@ -0,0 +1,106 @@
package org.firstinspires.ftc.teamcode.pedroPathing;
import com.pedropathing.drivetrain.Drivetrain;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.drivetrains.*;
import com.pedropathing.ftc.localization.constants.DriveEncoderConstants;
import com.pedropathing.ftc.localization.constants.OTOSConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.ftc.localization.constants.ThreeWheelConstants;
import com.pedropathing.ftc.localization.constants.ThreeWheelIMUConstants;
import com.pedropathing.ftc.localization.constants.TwoWheelConstants;
import com.pedropathing.ftc.localization.localizers.DriveEncoderLocalizer;
import com.pedropathing.ftc.localization.localizers.OTOSLocalizer;
import com.pedropathing.ftc.localization.localizers.PinpointLocalizer;
import com.pedropathing.ftc.localization.localizers.ThreeWheelIMULocalizer;
import com.pedropathing.ftc.localization.localizers.ThreeWheelLocalizer;
import com.pedropathing.ftc.localization.localizers.TwoWheelLocalizer;
import com.pedropathing.localization.Localizer;
import com.pedropathing.paths.PathConstraints;
import com.qualcomm.robotcore.hardware.HardwareMap;
/** This is the FollowerBuilder.
* It is used to create Followers with a specific drivetrain + localizer without having to use a full constructor
*
* @author Baron Henderson - 20077 The Indubitables
*/
public class FollowerBuilder {
private final FollowerConstants constants;
private PathConstraints constraints;
private final HardwareMap hardwareMap;
private Localizer localizer;
private Drivetrain drivetrain;
public FollowerBuilder(FollowerConstants constants, HardwareMap hardwareMap) {
this.constants = constants;
this.hardwareMap = hardwareMap;
constraints = PathConstraints.defaultConstraints;
}
public FollowerBuilder setLocalizer(Localizer localizer) {
this.localizer = localizer;
return this;
}
public FollowerBuilder driveEncoderLocalizer(DriveEncoderConstants lConstants) {
return setLocalizer(new DriveEncoderLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder OTOSLocalizer(OTOSConstants lConstants) {
return setLocalizer(new OTOSLocalizer(hardwareMap, lConstants));
}
PinpointLocalizer pinpointLocalizer;
public FollowerBuilder pinpointLocalizer(PinpointConstants lConstants) {
pinpointLocalizer = new PinpointLocalizer(hardwareMap, lConstants);
return setLocalizer(pinpointLocalizer);
}
public void resetPinpoint(){
pinpointLocalizer.resetIMU();
}
public void recalibrateIMU(){
pinpointLocalizer.recalibrate();
}
public FollowerBuilder threeWheelIMULocalizer(ThreeWheelIMUConstants lConstants) {
return setLocalizer(new ThreeWheelIMULocalizer(hardwareMap, lConstants));
}
public FollowerBuilder threeWheelLocalizer(ThreeWheelConstants lConstants) {
return setLocalizer(new ThreeWheelLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder twoWheelLocalizer(TwoWheelConstants lConstants) {
return setLocalizer(new TwoWheelLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder setDrivetrain(Drivetrain drivetrain) {
this.drivetrain = drivetrain;
return this;
}
public FollowerBuilder mecanumDrivetrain(MecanumConstants mecanumConstants) {
return setDrivetrain(new Mecanum(hardwareMap, mecanumConstants));
}
@Deprecated
public FollowerBuilder mecanumExDrivetrain(MecanumConstants mecanumConstants) {
return setDrivetrain(new MecanumEx(hardwareMap, mecanumConstants));
}
public FollowerBuilder swerveDrivetrain(SwerveConstants swerveConstants, SwervePod... pods) {
return setDrivetrain(new Swerve(hardwareMap, swerveConstants, pods));
}
public FollowerBuilder pathConstraints(PathConstraints pathConstraints) {
this.constraints = pathConstraints;
PathConstraints.setDefaultConstraints(pathConstraints);
return this;
}
public Follower build() {
return new Follower(constants, localizer, drivetrain, constraints);
}
}

View File

@@ -148,7 +148,7 @@ class LocalizationTest extends OpMode {
@Override @Override
public void init() { public void init() {
follower.setStartingPose(new Pose(72,72, 0)); follower.setStartingPose(new Pose(0,0, 0));
} }
/** This initializes the PoseUpdater, the drive motors, and the Panels telemetry. */ /** This initializes the PoseUpdater, the drive motors, and the Panels telemetry. */
@@ -1272,7 +1272,7 @@ class CentripetalTuner extends OpMode {
public void start() { public void start() {
follower.activateAllPIDFs(); follower.activateAllPIDFs();
forwards = new Path(new BezierCurve(new Pose(0,0), new Pose(Math.abs(DISTANCE) ,0), new Pose(Math.abs(DISTANCE) ,DISTANCE ))); forwards = new Path(new BezierCurve(new Pose(0,0), new Pose(Math.abs(DISTANCE) ,0), new Pose(Math.abs(DISTANCE) ,DISTANCE )));
backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72), new Pose(Math.abs(DISTANCE) ,0), new Pose(0,0))); backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 0,DISTANCE + 0), new Pose(Math.abs(DISTANCE) ,0), new Pose(0,0)));
backwards.setTangentHeadingInterpolation(); backwards.setTangentHeadingInterpolation();
backwards.reverseHeadingInterpolation(); backwards.reverseHeadingInterpolation();
@@ -1382,14 +1382,14 @@ class Circle extends OpMode {
public void start() { public void start() {
circle = follower.pathBuilder() circle = follower.pathBuilder()
.addPath(new BezierCurve(new Pose(72, 72), new Pose(RADIUS + 72, 72), new Pose(RADIUS + 72, RADIUS + 72))) .addPath(new BezierCurve(new Pose(0, 0), new Pose(RADIUS + 0, 0), new Pose(RADIUS + 0, RADIUS + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(RADIUS + 72, RADIUS + 72), new Pose(RADIUS + 72, (2 * RADIUS) + 72), new Pose(72, (2 * RADIUS) + 72))) .addPath(new BezierCurve(new Pose(RADIUS + 0, RADIUS + 0), new Pose(RADIUS + 0, (2 * RADIUS) + 0), new Pose(0, (2 * RADIUS) + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, RADIUS + 72))) .addPath(new BezierCurve(new Pose(0, (2 * RADIUS) + 0), new Pose(-RADIUS + 0, (2 * RADIUS) + 0), new Pose(-RADIUS + 0, RADIUS + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(-RADIUS + 72, RADIUS + 72), new Pose(-RADIUS + 72, 72), new Pose(72, 72))) .addPath(new BezierCurve(new Pose(-RADIUS + 0, RADIUS + 0), new Pose(-RADIUS + 0, 0), new Pose(0, 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.build(); .build();
follower.followPath(circle); follower.followPath(circle);
} }
@@ -1406,7 +1406,7 @@ class Circle extends OpMode {
@Override @Override
public void init() { public void init() {
follower.setStartingPose(new Pose(72, 72)); follower.setStartingPose(new Pose(0, 0));
} }
/** /**
@@ -1639,8 +1639,8 @@ class OffsetsTuner extends OpMode {
telemetry.addLine("Total Angle: " + follower.getTotalHeading()); telemetry.addLine("Total Angle: " + follower.getTotalHeading());
telemetry.addLine("The following values are the offsets in inches that should be applied to your localizer."); telemetry.addLine("The following values are the offsets in inches that should be applied to your localizer.");
telemetry.addLine("strafeX: " + ((72.0-follower.getPose().getX()) / 2.0)); telemetry.addLine("strafeX: " + ((0.0-follower.getPose().getX()) / 2.0));
telemetry.addLine("forwardY: " + ((72.0-follower.getPose().getY()) / 2.0)); telemetry.addLine("forwardY: " + ((0.0-follower.getPose().getY()) / 2.0));
telemetry.update(); telemetry.update();
drawCurrentAndHistory(); drawCurrentAndHistory();

View File

@@ -1,9 +1,5 @@
package org.firstinspires.ftc.teamcode.teleop; package org.firstinspires.ftc.teamcode.teleop;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
@@ -12,10 +8,15 @@ import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.robotcore.external.navigation.CurrentUnit;
import org.firstinspires.ftc.teamcode.constants.Color; import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.*; import org.firstinspires.ftc.teamcode.utilsv2.*;
import static org.firstinspires.ftc.teamcode.utilsv2.Turret.limelightUsed;
@TeleOp @TeleOp
@Config @Config
public class TeleopV4 extends LinearOpMode { public class TeleopV4 extends LinearOpMode {
@@ -25,47 +26,174 @@ public class TeleopV4 extends LinearOpMode {
MultipleTelemetry TELE; MultipleTelemetry TELE;
Follower follower; Follower follower;
SpindexerTransferIntake spindexerTransferIntake; SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
ParkTilter parkTilter;
MeasuringLoopTimes loopTimes;
public static Pose relocalizePose = new Pose(54.7, 11.4, 0);
public static Pose teleStart = new Pose(0,0,0);
private boolean firstTickFull = true;
private boolean intakeFull = true;
private boolean shooting = false;
public static int flywheelOffset = 0;
public static double hoodOffset = 0;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap); robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry( TELE = new MultipleTelemetry(
FtcDashboard.getInstance().getTelemetry(), telemetry FtcDashboard.getInstance().getTelemetry(), telemetry
); );
commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE); drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap); follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH)); follower.setStartingPose(teleStart);
follower.setStartingPose(start); sleep(500);
follower.setPose(teleStart);
follower.update();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance); flywheel = new Flywheel(robot);
turret = new Turret(robot);
parkTilter = new ParkTilter(robot);
parkTilter.unpark();
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
shooter.setState(Shooter.ShooterState.TRACK_GOAL); shooter.setState(Shooter.ShooterState.TRACK_GOAL);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE); shooter.setRedAlliance(Color.redAlliance);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID); spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
TELE.addLine("Initialization is done");
TELE.addData("Starting Position", follower.getPose());
TELE.addData("TELE START", teleStart);
TELE.update();
while (opModeInInit()){
if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
VelocityCommander.lockBack = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
} else if (gamepad1.squareWasPressed()){
VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SPINDEXER_BACK);
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
}
TELE.addLine("Initialization is done");
TELE.addData("Starting Position", follower.getPose());
TELE.addData("TELE START", teleStart);
TELE.addData("Front?:", VelocityCommander.lockFront);
TELE.addData("Back?:", VelocityCommander.lockBack);
TELE.update();
}
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
int emptyTicks = 0;
while (opModeIsActive()) { while (opModeIsActive()) {
//Drivetrain //Drivetrain
drivetrain.drive( drivetrain.drive(
-gamepad1.right_stick_y, -gamepad1.right_stick_y,
gamepad1.right_stick_x, gamepad1.right_stick_x,
gamepad1.left_stick_x gamepad1.left_stick_x,
gamepad1.left_trigger
); );
shooter.update(); if (gamepad1.crossWasPressed()){
if (Color.redAlliance){
relocalizePose = new Pose(54.4, 12, 0);
} else {
relocalizePose = new Pose(-54.4, 12, Math.toRadians(180));
}
follower.setPose(relocalizePose);
sleep(500);
gamepad1.rumble(100);
}
if (!isStopRequested()){
follower.update();
}
Pose currentPose = follower.getPose();
teleStart = currentPose;
if (gamepad1.dpadLeftWasPressed()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
}
if (gamepad1.dpadRightWasPressed()){
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
}
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(2500 + flywheelOffset);
robot.setHoodPos(0.6 + hoodOffset);
}
if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
VelocityCommander.lockBack = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.INTAKE);
TELE.addData("Front?:", true);
TELE.addData("Back?:", false);
} else if (gamepad1.squareWasPressed()){
VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SPINDEXER_BACK);
spindexerTransferIntake.setSortedIntakeMode(SpindexerTransferIntake.SortedIntakeStates.IDLE);
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.INTAKE);
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
}
shooter.update(robot.voltage.getVoltage());
spindexerTransferIntake.update(); spindexerTransferIntake.update();
if (VelocityCommander.lockBack){
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Open);
if (gamepad1.leftBumperWasPressed()){
spindexerTransferIntake.startBackShooting();
firstTickFull = true;
}
if (spindexerTransferIntake.getSortedIntakeStates() == SpindexerTransferIntake.SortedIntakeStates.REVERSE && firstTickFull){
gamepad1.rumble(100);
firstTickFull = false;
}
TELE.addData("Intake State", spindexerTransferIntake.getSortedIntakeStates());
} else {
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState(); SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
if (gamepad1.xWasPressed() && if (gamepad1.leftBumperWasPressed() &&
(state == SpindexerTransferIntake.RapidMode.INTAKE || (state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF || state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT || state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
@@ -74,9 +202,23 @@ public class TeleopV4 extends LinearOpMode {
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) { state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE); spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
intakeFull = false;
firstTickFull = true;
shooting = true;
} }
if (gamepad1.aWasPressed() && if (state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT){
shooting = false;
}
if (SpindexerTransferIntake.intakeFull && firstTickFull){
gamepad1.rumble(250);
firstTickFull = false;
} else if (!SpindexerTransferIntake.intakeFull){
firstTickFull = true;
}
if (gamepad1.right_trigger > 0.5 &&
(state == SpindexerTransferIntake.RapidMode.INTAKE || (state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) { state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
@@ -85,15 +227,76 @@ public class TeleopV4 extends LinearOpMode {
); );
} }
if (gamepad1.yWasPressed() if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) { robot.setIntakePower(1);
robot.setTransferPower(-0.7);
spindexerTransferIntake.setRapidMode( }
SpindexerTransferIntake.RapidMode.INTAKE
);
} }
if (gamepad2.leftBumperWasPressed()){
limelightUsed = false;
} else if (gamepad2.rightBumperWasPressed()){
limelightUsed = true;
}
if (gamepad1.dpad_down){
parkTilter.park();
} else if (gamepad1.dpad_up) {
parkTilter.unpark();
}
if (gamepad2.leftBumperWasPressed()){
limelightUsed = false;
} else if (gamepad2.rightBumperWasPressed()){
limelightUsed = true;
}
if (gamepad2.dpadUpWasPressed()){
hoodOffset-=0.02;
} else if (gamepad2.dpadDownWasPressed()){
hoodOffset+=0.02;
}
if (gamepad2.dpadRightWasPressed()){
flywheelOffset+=50;
} else if (gamepad2.dpadLeftWasPressed()){
flywheelOffset-=50;
}
if (gamepad2.crossWasPressed()){
flywheelOffset = 0;
hoodOffset = 0;
}
loopTimes.loop();
// TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
// TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
// TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
//
// TELE.addData("Distance From Goal", commander.getDistance());
// TELE.addData("Hood Position", commander.getHoodPredicted());
// TELE.addData("Transfer Power", robot.transfer.getPower());
// TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
// TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
// TELE.addData("Velocity 1", flywheel.getVelo1());
// TELE.addData("Velocity 2", flywheel.getVelo2());
TELE.addData("Flywheel Offset", flywheelOffset);
TELE.addData("Hood Offset", hoodOffset);
// TELE.addData("FR Drive", robot.frontRight.getCurrent(CurrentUnit.AMPS));
// TELE.addData("FL Drive", robot.frontRight.getCurrent(CurrentUnit.AMPS));
// TELE.addData("BL Drive", robot.backLeft.getCurrent(CurrentUnit.AMPS));
// TELE.addData("BR Drive", robot.backRight.getCurrent(CurrentUnit.AMPS));
// TELE.addData("Flywheel 1", robot.shooter1.getCurrent(CurrentUnit.AMPS));
// TELE.addData("Flywheel 2", robot.shooter2.getCurrent(CurrentUnit.AMPS));
// TELE.addData("Transfer", robot.transfer.getCurrent(CurrentUnit.AMPS));
// TELE.addData("Intake", robot.intake.getCurrent(CurrentUnit.AMPS));
//
// TELE.addData("Current Position", currentPose);
//
// TELE.addData("Current LL Pipeline", turret.pipeline());
//
TELE.update(); TELE.update();
} }

View File

@@ -9,8 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam; import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class AprilTagWebcamExample extends OpMode { public class AprilTagWebcamExample extends OpMode {
MultipleTelemetry TELE; MultipleTelemetry TELE;

View File

@@ -12,8 +12,7 @@ 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;
@Config
@TeleOp
public class ColorTest extends LinearOpMode { public class ColorTest extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;

View File

@@ -130,8 +130,8 @@ public class Hardware_Tester extends LinearOpMode {
// TELE.addData("Beam Break 3?", robot.beam3.isPressed()); // TELE.addData("Beam Break 3?", robot.beam3.isPressed());
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors(); NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.MM)); TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.CM));
TELE.addData("REV Green", revColor.green / (revColor.red + revColor.blue + revColor.green)); TELE.addData("REV Green", revColor.green / (revColor.green + revColor.blue + revColor.red));
TELE.addData("Voltage Sensor", robot.voltage.getVoltage()); TELE.addData("Voltage Sensor", robot.voltage.getVoltage());

View File

@@ -7,8 +7,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class MotorDirectionDebugger extends LinearOpMode { public class MotorDirectionDebugger extends LinearOpMode {
public static double flPower = 0.0; public static double flPower = 0.0;

View File

@@ -3,43 +3,40 @@ package org.firstinspires.ftc.teamcode.tests;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.ServoPositions; import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel; import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.utilsv2.Robot; import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.Shooter; import org.firstinspires.ftc.teamcode.utilsv2.*;
import static org.firstinspires.ftc.teamcode.utilsv2.Turret.limelightUsed;
@Config
@TeleOp @TeleOp
@Config
public class NewShooterTest extends LinearOpMode { public class NewShooterTest extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; Drivetrain drivetrain;
Shooter shooter; Shooter shooter;
Flywheel rpmFlywheel; MultipleTelemetry TELE;
Follower follower;
SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
ParkTilter parkTilter;
MeasuringLoopTimes loopTimes;
public static boolean intake = true; private boolean firstTickFull = true;
public static boolean shoot = false; private boolean intakeFull = true;
public static double intakePower = 1.0; private boolean shooting = false;
public static double transferShootPower = -1; public static int flywheelVelo = 0;
public static double transferIntakePower = -1; public static double hoodPos = 0.5;
public static double turretPos = 0.51; public static double transferPower = -0.8;
public static double hoodPos = 0.51;
public static double flywheel = 0;
public static double shooterP = 255, shooterI = 0, shooterD = 0, shooterF = 75;
private enum ShootState {
IDLE,
WAIT_GATE,
WAIT_PUSH
}
private ShootState shootState = ShootState.IDLE;
private long timestamp = 0;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
@@ -48,95 +45,212 @@ public class NewShooterTest extends LinearOpMode {
robot = Robot.getInstance(hardwareMap); robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(
FtcDashboard.getInstance().getTelemetry(), telemetry
shooter = new Shooter(
robot,
TELE,
Constants.createFollower(hardwareMap),
true
); );
rpmFlywheel = new Flywheel(robot); commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap);
follower.setStartingPose(new Pose(0,0,0));
sleep(500);
follower.setPose(new Pose(0,0,0));
follower.update();
shooter.setState(Shooter.ShooterState.MANUAL); flywheel = new Flywheel(robot);
turret = new Turret(robot);
parkTilter = new ParkTilter(robot);
parkTilter.unpark();
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.setRedAlliance(Color.redAlliance);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
TELE.addLine("Initialization is done");
TELE.update();
while (opModeInInit()){
if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
VelocityCommander.lockBack = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
} else if (gamepad1.squareWasPressed()){
VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SPINDEXER_BACK);
spindexerTransferIntake.setSortedIntakeMode(SpindexerTransferIntake.SortedIntakeStates.IDLE);
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
}
TELE.addLine("Initialization is done");
TELE.addData("Front?:", VelocityCommander.lockFront);
TELE.addData("Back?:", VelocityCommander.lockBack);
TELE.update();
}
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
while (opModeIsActive()) { while (opModeIsActive()) {
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x,
gamepad1.left_trigger
);
if (gamepad1.crossWasPressed()){
if (Color.redAlliance){
TeleopV4.relocalizePose = new Pose(57.5, 5, 0);
} else {
TeleopV4.relocalizePose = new Pose(-57.5, 5, Math.toRadians(180));
}
follower.setPose(TeleopV4.relocalizePose);
sleep(500);
gamepad1.rumble(100);
}
follower.update();
Pose currentPose = follower.getPose();
if (gamepad1.dpadLeftWasPressed()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
}
if (gamepad1.dpadRightWasPressed()){
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
}
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(flywheelVelo);
robot.setHoodPos(hoodPos); robot.setHoodPos(hoodPos);
shooter.setTurretPosition(turretPos);
shooter.setFlywheelVelocity(flywheel);
rpmFlywheel.manageFlywheel(shooter.getFlywheelVelocity());
double voltage = robot.voltage.getVoltage();
rpmFlywheel.setPIDF(shooterP, shooterI, shooterD, shooterF / voltage);
robot.setSpinPos(ServoPositions.spindexer_A2);
if (intake && !shoot) {
shootState = ShootState.IDLE;
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Closed);
robot.setTransferPower(transferIntakePower);
robot.setIntakePower(intakePower);
robot.setTransferServoPos(
ServoPositions.transferServo_out);
} else if (shoot) {
robot.setIntakePower(intakePower);
switch (shootState) {
case IDLE:
robot.setTransferPower(transferShootPower);
timestamp = System.currentTimeMillis();
shootState = ShootState.WAIT_GATE;
break;
case WAIT_GATE:
if (System.currentTimeMillis() - timestamp >= 300) {
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open);
timestamp = System.currentTimeMillis();
shootState = ShootState.WAIT_PUSH;
} }
break; if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
case WAIT_PUSH: VelocityCommander.lockBack = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
if (System.currentTimeMillis() - timestamp >= 100) { TELE.addData("Front?:", true);
TELE.addData("Back?:", false);
robot.setTransferServoPos( } else if (gamepad1.squareWasPressed()){
ServoPositions.transferServo_in); VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
shootState = ShootState.IDLE; spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SPINDEXER_BACK);
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
} }
break; shooter.update(robot.voltage.getVoltage());
spindexerTransferIntake.update();
if (VelocityCommander.lockBack){
if (gamepad1.leftBumperWasPressed() && spindexerTransferIntake.getSortedIntakeStates() == SpindexerTransferIntake.SortedIntakeStates.REVERSE){
spindexerTransferIntake.startBackShooting();
firstTickFull = true;
}
if (spindexerTransferIntake.getSortedIntakeStates() == SpindexerTransferIntake.SortedIntakeStates.REVERSE && firstTickFull){
gamepad1.rumble(100);
firstTickFull = false;
}
} else {
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
if (gamepad1.leftBumperWasPressed() &&
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
state == SpindexerTransferIntake.RapidMode.PULSE_OUT ||
state == SpindexerTransferIntake.RapidMode.PULSE_IN ||
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
intakeFull = false;
firstTickFull = true;
shooting = true;
}
if (state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT){
shooting = false;
}
if (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed() && !shooting){
intakeFull = true;
} else {
intakeFull = false;
firstTickFull = true;
}
if (intakeFull && firstTickFull){
gamepad1.rumble(100);
firstTickFull = false;
}
if (gamepad1.right_trigger > 0.5 &&
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
spindexerTransferIntake.setRapidMode(
SpindexerTransferIntake.RapidMode.HOLD_BALLS
);
}
if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
robot.setIntakePower(1);
robot.setTransferPower(-0.7);
} }
} }
TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28); if (gamepad2.leftBumperWasPressed()){
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28); limelightUsed = false;
TELE.addData("Flywheel Averag Velocity", rpmFlywheel.getAverageVelocity()); } else if (gamepad2.rightBumperWasPressed()){
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF); limelightUsed = true;
TELE.addData("Power", rpmFlywheel.getShooterPower()); }
if (gamepad1.dpad_down){
parkTilter.park();
} else if (gamepad1.dpad_up) {
parkTilter.unpark();
}
loopTimes.loop();
// TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
// TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
// TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
//
TELE.addData("Distance From Goal", commander.getDistance());
// TELE.addData("Hood Position", commander.getHoodPredicted());
// TELE.addData("Transfer Power", robot.transfer.getPower());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
//
// TELE.addData("Current Position", currentPose);
//
// TELE.addData("Current LL Pipeline", turret.pipeline());
//
TELE.update(); TELE.update();
}
shooter.update();
}
} }
} }

View File

@@ -27,8 +27,6 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@TeleOp
public class ShooterTest extends LinearOpMode { public class ShooterTest extends LinearOpMode {
public static int mode = 1; public static int mode = 1;
public static double parameter = 0.0; public static double parameter = 0.0;

View File

@@ -0,0 +1,126 @@
package org.firstinspires.ftc.teamcode.tests;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.*;
@TeleOp
@Config
public class SortedSpindexerTest extends LinearOpMode {
Robot robot;
Drivetrain drivetrain;
Shooter shooter;
MultipleTelemetry TELE;
Follower follower;
SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
ParkTilter parkTilter;
public static String order = "GPP";
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(
FtcDashboard.getInstance().getTelemetry(), telemetry
);
commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start);
flywheel = new Flywheel(robot);
turret = new Turret(robot);
parkTilter = new ParkTilter(robot);
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
shooter.setRedAlliance(Color.redAlliance);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SORTED);
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
switch(order) {
case "PPG":
spindexerTransferIntake.setDesiredPattern(
SpindexerTransferIntake.DesiredPattern.PPG
);
break;
case "PGP":
spindexerTransferIntake.setDesiredPattern(
SpindexerTransferIntake.DesiredPattern.PGP
);
break;
default:
spindexerTransferIntake.setDesiredPattern(
SpindexerTransferIntake.DesiredPattern.GPP
);
}
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x,
gamepad1.left_trigger
);
follower.update();
shooter.update(robot.voltage.getVoltage());
spindexerTransferIntake.update();
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
if(gamepad1.leftBumperWasPressed()) {
spindexerTransferIntake.startSortedShoot();
}
if (gamepad1.dpad_down){
parkTilter.park();
} else if (gamepad1.dpad_up) {
parkTilter.unpark();
}
TELE.addData("Distance From Goal", commander.getDistance());
TELE.addData("Hood Position", commander.getHoodPredicted());
TELE.addData("Transfer Power", robot.transfer.getPower());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
TELE.update();
}
}
}

View File

@@ -18,8 +18,6 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@TeleOp
public class SortingTest extends LinearOpMode { public class SortingTest extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;

View File

@@ -15,8 +15,6 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Turret; import org.firstinspires.ftc.teamcode.utils.Turret;
@TeleOp
@Config
public class TurretTest extends LinearOpMode { public class TurretTest extends LinearOpMode {
public static boolean zeroTurr = false; public static boolean zeroTurr = false;
@Override @Override

View File

@@ -7,7 +7,6 @@ import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.StateEnums.LightState; import org.firstinspires.ftc.teamcode.constants.StateEnums.LightState;
@Config
public final class Light { public final class Light {
private static Light instance; private static Light instance;

View File

@@ -43,13 +43,12 @@ public class MeasuringLoopTimes {
public void loop() { public void loop() {
currentTime = getTimeSeconds(); currentTime = getTimeSeconds();
if ((MeasurementStart + 5.0) < currentTime) if ((MeasurementStart + 60) < currentTime)
{ {
minLoopTime = 9999999.0; minLoopTime = 9999999.0;
maxLoopTime = 0.0; maxLoopTime = 0.0;
MeasurementStart = currentTime; MeasurementStart = currentTime;
avgLoopTime = avgLoopTimeSum / (double) avgLoopTimeTicker;
avgLoopTimeSum = 0.0; avgLoopTimeSum = 0.0;
avgLoopTimeTicker = 0; avgLoopTimeTicker = 0;
} }
@@ -59,6 +58,7 @@ public class MeasuringLoopTimes {
avgLoopTimeSum += mainLoopTime; avgLoopTimeSum += mainLoopTime;
avgLoopTimeTicker++; avgLoopTimeTicker++;
avgLoopTime = avgLoopTimeSum / (double) avgLoopTimeTicker;
minLoopTime = Math.min(minLoopTime,mainLoopTime); minLoopTime = Math.min(minLoopTime,mainLoopTime);
maxLoopTime = Math.max(maxLoopTime,mainLoopTime); maxLoopTime = Math.max(maxLoopTime,mainLoopTime);
} }

View File

@@ -10,8 +10,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
@TeleOp
@Config
public class PositionalServoProgrammer extends LinearOpMode { public class PositionalServoProgrammer extends LinearOpMode {
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;

View File

@@ -16,7 +16,6 @@ import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
@Config
public class Robot { public class Robot {
//Initialize Public Components //Initialize Public Components

View File

@@ -6,7 +6,6 @@ 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;
@Config
public class Servos { public class Servos {
//PID constants //PID constants
// TODO: get PIDF constants // TODO: get PIDF constants

View File

@@ -19,7 +19,6 @@ import org.firstinspires.ftc.teamcode.teleop.TeleopV3;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.List; import java.util.List;
@Config
public class Turret { public class Turret {

View File

@@ -37,7 +37,7 @@ public class Drivetrain {
tele = input; tele = input;
} }
public void drive(double y, double x, double rx) { public void drive(double y, double x, double rx, double stop) {
boolean snappedForward = false; boolean snappedForward = false;
boolean snappedStrafe = false; boolean snappedStrafe = false;
@@ -79,18 +79,30 @@ public class Drivetrain {
robot.setFrontRightPower(frontRightPower); robot.setFrontRightPower(frontRightPower);
robot.setBackRightPower(backRightPower); robot.setBackRightPower(backRightPower);
if (tele) { if (stop > 0.5){
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
telemetry.addData("Forward Snap", snappedForward); robot.setFrontLeftPower(0);
telemetry.addData("Strafe Snap", snappedStrafe); robot.setBackLeftPower(0);
robot.setFrontRightPower(0);
telemetry.addData("Correction RX", correctionRX); robot.setBackRightPower(0);
}
telemetry.addData("FL", frontLeftPower);
telemetry.addData("BL", backLeftPower);
telemetry.addData("FR", frontRightPower);
telemetry.addData("BR", backRightPower);
} // if (tele) {
//
// telemetry.addData("Forward Snap", snappedForward);
// telemetry.addData("Strafe Snap", snappedStrafe);
//
// telemetry.addData("Correction RX", correctionRX);
//
// telemetry.addData("FL", frontLeftPower);
// telemetry.addData("BL", backLeftPower);
// telemetry.addData("FR", frontRightPower);
// telemetry.addData("BR", backRightPower);
//
// }
} }
} }

View File

@@ -1,5 +1,8 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PIDFController;
import com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
@@ -9,15 +12,26 @@ import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import java.util.LinkedList; import java.util.LinkedList;
@Config
public class Flywheel { public class Flywheel {
Robot robot; Robot robot;
// public PIDFCoefficients shooterPIDF1, shooterPIDF2; // public PIDFCoefficients shooterPIDF1, shooterPIDF2;
public static PIDFCoefficients shooterPIDF; public static PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255; PIDFController pidf;
public static double shooterPIDF_I = 0.0; SimpleMotorFeedforward feedforward;
public static double kS = 0.01; // Static feedforward
public static double kV = 0.0001935; // Velocity feedforward
public static double shooterPIDF_P = 500;
public static double shooterPIDF_I = 1;
public static double shooterPIDF_D = 0.0; public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75; public static double shooterPIDF_F = 93;
// public static double shooterPIDF_P = 0.0001;
// public static double shooterPIDF_I = 0;
// public static double shooterPIDF_D = 0.00001;
// public static double shooterPIDF_F = 0;
private double velo = 0.0; private double velo = 0.0;
private double velo1 = 0.0; private double velo1 = 0.0;
@@ -34,6 +48,8 @@ public class Flywheel {
public Flywheel(Robot rob) { public Flywheel(Robot rob) {
robot = rob; robot = rob;
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12); shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
// pidf = new PIDFController(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, 0);
// feedforward = new SimpleMotorFeedforward(kS, kV);
} }
public double getVelo() { public double getVelo() {
@@ -65,19 +81,32 @@ public class Flywheel {
shooterPIDF.d = d; shooterPIDF.d = d;
shooterPIDF.f = f; shooterPIDF.f = f;
// pidf.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, 0);
if (velo1 != 0){
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
} else {
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
}
} }
private double prevF = 0; private double prevF = 0;
public static double voltagePIDFDifference = 1;
public static double voltagePIDFDifference = 0.8; double averageVoltage = 0;
public void setF(double f){ public void setF(double voltage){
if (Math.abs(prevF - f) > voltagePIDFDifference) { averageVoltage = ALPHA * voltage + (1 - ALPHA) * averageVoltage;
double f = shooterPIDF_F / voltage;
if (Math.abs(prevF - f) > voltagePIDFDifference && !steady) {
shooterPIDF.f = f; shooterPIDF.f = f;
if (velo1 != 0){
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f; } else {
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
} }
} }
prevF = f;
}
// Convert from RPM to Ticks per Second // Convert from RPM to Ticks per Second
private double RPM_to_TPS(double RPM) { private double RPM_to_TPS(double RPM) {
@@ -89,44 +118,72 @@ public class Flywheel {
return (TPS * 60.0) / 28.0; return (TPS * 60.0) / 28.0;
} }
double ALPHA = 0.3;
private void updateVelocityAverage(double newVelocity) { private void updateVelocityAverage(double newVelocity) {
velocityHistory.add(newVelocity); // velocityHistory.add(newVelocity);
//
// int velocityHistorySize = 5;
// if (velocityHistory.size() > velocityHistorySize) {
// velocityHistory.removeFirst();
// }
//
// double sum = 0.0;
//
// for (double v : velocityHistory) {
// sum += v;
// }
//
// averageVelocity = sum / velocityHistory.size();
int velocityHistorySize = 5; averageVelocity = ALPHA * newVelocity + (1 - ALPHA) * averageVelocity;
if (velocityHistory.size() > velocityHistorySize) {
velocityHistory.removeFirst();
}
double sum = 0.0;
for (double v : velocityHistory) {
sum += v;
}
averageVelocity = sum / velocityHistory.size();
} }
double power; double power;
double prevTargetTime = 0;
double prevTargetVelocity = 0;
int veloMode = 0;
public void 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;
} }
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity)); if (velo1 < 100){
power = robot.shooter1.getPower();
robot.shooter2.setPower(power);
}
velo1 = TPS_to_RPM(robot.shooter1.getVelocity()); velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
velo2 = TPS_to_RPM(robot.shooter2.getVelocity()); velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = (velo1 + velo2) / 2.0; if (velo1 < 100){
velo1 = 0;
velo = velo2;
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
if (veloMode != 2){
robot.shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
robot.shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
veloMode = 2;
}
power = robot.shooter2.getPower();
robot.shooter1.setPower(power);
} else {
velo2 = 0;
velo = velo1;
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
if (veloMode != 1){
robot.shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
robot.shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
veloMode = 1;
}
power = robot.shooter1.getPower();
robot.shooter2.setPower(power);
}
updateVelocityAverage(velo); updateVelocityAverage(velo);
steady = (Math.abs(commandedVelocity - averageVelocity) < 50); steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
} }
public double getShooterPower(){return power;} public double getShooterPower(){return power;}
} }

View File

@@ -0,0 +1,22 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.qualcomm.robotcore.hardware.Servo;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
public class ParkTilter {
Robot robot;
public ParkTilter (Robot rob) {
this.robot = rob;
}
public void park() {
robot.setTilt1Pos(ServoPositions.tilt1_down);
robot.setTilt2Pos(ServoPositions.tilt2_down);
}
public void unpark() {
robot.setTilt1Pos(ServoPositions.tilt1_up);
robot.setTilt2Pos(ServoPositions.tilt2_up);
}
}

View File

@@ -15,6 +15,7 @@ import com.qualcomm.robotcore.hardware.TouchSensor;
import com.qualcomm.robotcore.hardware.VoltageSensor; import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.robotcore.external.navigation.CurrentUnit;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
public class Robot { public class Robot {
@@ -80,6 +81,11 @@ public class Robot {
public Limelight3A limelight; public Limelight3A limelight;
public Servo light; public Servo light;
// Current Limits
public static double intakeCurrentLimit = 6.0;
public static double transferCurrentLimit = 5.0;
public static double drivetrainCurrentLimit = 7.0;
public Robot(HardwareMap hardwareMap) { public Robot(HardwareMap hardwareMap) {
//Define components w/ hardware map //Define components w/ hardware map
@@ -120,7 +126,6 @@ public class Robot {
transfer = hardwareMap.get(DcMotorEx.class, "transfer"); transfer = hardwareMap.get(DcMotorEx.class, "transfer");
transferServo = hardwareMap.get(Servo.class, "transferServo"); transferServo = hardwareMap.get(Servo.class, "transferServo");
transfer.setDirection(DcMotorSimple.Direction.REVERSE); transfer.setDirection(DcMotorSimple.Direction.REVERSE);
@@ -138,6 +143,13 @@ public class Robot {
revSensor = hardwareMap.get(RevColorSensorV3.class, "rev"); revSensor = hardwareMap.get(RevColorSensorV3.class, "rev");
frontLeft.setCurrentAlert(drivetrainCurrentLimit, CurrentUnit.AMPS);
frontRight.setCurrentAlert(drivetrainCurrentLimit, CurrentUnit.AMPS);
backLeft.setCurrentAlert(drivetrainCurrentLimit, CurrentUnit.AMPS);
backRight.setCurrentAlert(drivetrainCurrentLimit, CurrentUnit.AMPS);
intake.setCurrentAlert(intakeCurrentLimit, CurrentUnit.AMPS);
transfer.setCurrentAlert(transferCurrentLimit, CurrentUnit.AMPS);
// Below is disregarded // Below is disregarded
// turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port // turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
@@ -169,12 +181,18 @@ public class Robot {
// Voids below are used to minimize hardware calls to minimize loop times // Voids below are used to minimize hardware calls to minimize loop times
// Used to cut off digits that are negligible // Used to cut off digits that are negligible
private final int maxDigits = 5; private final int maxDigits = 3;
private final int roundingFactor = (int) Math.pow(10, maxDigits); private final int roundingFactor = (int) Math.pow(10, maxDigits);
private double prevFrontLeftPower = -10.501; private double prevFrontLeftPower = -10.501;
public void setFrontLeftPower(double pow){ public void setFrontLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; if (frontLeft.isOverCurrent()){
double current = frontLeft.getCurrent(CurrentUnit.AMPS);
if (current != 0) {
pow = pow * drivetrainCurrentLimit / current;
}
}
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevFrontLeftPower){ if (pow != prevFrontLeftPower){
frontLeft.setPower(pow); frontLeft.setPower(pow);
} }
@@ -183,7 +201,13 @@ public class Robot {
private double prevFrontRightPower = -10.501; private double prevFrontRightPower = -10.501;
public void setFrontRightPower(double pow){ public void setFrontRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; if (frontRight.isOverCurrent()){
double current = frontRight.getCurrent(CurrentUnit.AMPS);
if (current != 0) {
pow = pow * drivetrainCurrentLimit / current;
}
}
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevFrontRightPower){ if (pow != prevFrontRightPower){
frontRight.setPower(pow); frontRight.setPower(pow);
} }
@@ -192,7 +216,13 @@ public class Robot {
private double prevBackLeftPower = -10.501; private double prevBackLeftPower = -10.501;
public void setBackLeftPower(double pow){ public void setBackLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; if (backLeft.isOverCurrent()){
double current = backLeft.getCurrent(CurrentUnit.AMPS);
if (current != 0) {
pow = pow * drivetrainCurrentLimit / current;
}
}
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevBackLeftPower){ if (pow != prevBackLeftPower){
backLeft.setPower(pow); backLeft.setPower(pow);
} }
@@ -201,7 +231,13 @@ public class Robot {
private double prevBackRightPower = -10.501; private double prevBackRightPower = -10.501;
public void setBackRightPower(double pow){ public void setBackRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; if (backRight.isOverCurrent()){
double current = backRight.getCurrent(CurrentUnit.AMPS);
if (current != 0) {
pow = pow * drivetrainCurrentLimit / current;
}
}
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevBackRightPower){ if (pow != prevBackRightPower){
backRight.setPower(pow); backRight.setPower(pow);
} }
@@ -210,7 +246,13 @@ public class Robot {
private double prevIntakePower = -10.501; private double prevIntakePower = -10.501;
public void setIntakePower(double pow){ public void setIntakePower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; if (intake.isOverCurrent()){
double current = intake.getCurrent(CurrentUnit.AMPS);
if (current != 0) {
pow = pow * intakeCurrentLimit / current;
}
}
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevIntakePower){ if (pow != prevIntakePower){
intake.setPower(pow); intake.setPower(pow);
} }
@@ -219,7 +261,13 @@ public class Robot {
private double prevTransferPower = -10.501; private double prevTransferPower = -10.501;
public void setTransferPower(double pow){ public void setTransferPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor; pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
// if (transfer.isOverCurrent()){
// double current = transfer.getCurrent(CurrentUnit.AMPS);
// if (current != 0) {
// pow = pow * transferCurrentLimit / current;
// }
// }
if (pow != prevTransferPower){ if (pow != prevTransferPower){
transfer.setPower(pow); transfer.setPower(pow);
} }
@@ -230,7 +278,7 @@ public class Robot {
private double prevHoodPos = -10.501; private double prevHoodPos = -10.501;
public void setHoodPos(double pos){ public void setHoodPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevHoodPos){ if (pos != prevHoodPos){
hood.setPosition(pos); hood.setPosition(pos);
} }
@@ -239,7 +287,7 @@ public class Robot {
private double prevTransferServoPos = -10.501; private double prevTransferServoPos = -10.501;
public void setTransferServoPos(double pos){ public void setTransferServoPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTransferServoPos){ if (pos != prevTransferServoPos){
transferServo.setPosition(pos); transferServo.setPosition(pos);
} }
@@ -248,7 +296,7 @@ public class Robot {
private double prevSpinPos = -10.501; private double prevSpinPos = -10.501;
public void setSpinPos(double pos){ public void setSpinPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevSpinPos){ if (pos != prevSpinPos){
spin1.setPosition(pos); spin1.setPosition(pos);
spin2.setPosition(pos); spin2.setPosition(pos);
@@ -258,7 +306,7 @@ public class Robot {
private double prevTurretPos = -10.501; private double prevTurretPos = -10.501;
public void setTurretPos(double pos){ public void setTurretPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTurretPos){ if (pos != prevTurretPos){
turr1.setPosition(pos); turr1.setPosition(pos);
turr2.setPosition(pos); turr2.setPosition(pos);
@@ -268,7 +316,7 @@ public class Robot {
private double prevTilt1Pos = -10.501; private double prevTilt1Pos = -10.501;
public void setTilt1Pos(double pos){ public void setTilt1Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTilt1Pos){ if (pos != prevTilt1Pos){
tilt1.setPosition(pos); tilt1.setPosition(pos);
} }
@@ -277,7 +325,7 @@ public class Robot {
private double prevTilt2Pos = -10.501; private double prevTilt2Pos = -10.501;
public void setTilt2Pos(double pos){ public void setTilt2Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTilt2Pos){ if (pos != prevTilt2Pos){
tilt2.setPosition(pos); tilt2.setPosition(pos);
} }
@@ -286,7 +334,7 @@ public class Robot {
private double prevSpindexBlockerPos = -10.501; private double prevSpindexBlockerPos = -10.501;
public void setSpindexBlockerPos(double pos){ public void setSpindexBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevSpindexBlockerPos){ if (pos != prevSpindexBlockerPos){
spindexBlocker.setPosition(pos); spindexBlocker.setPosition(pos);
} }
@@ -295,7 +343,7 @@ public class Robot {
private double prevRapidFireBlockerPos = -10.501; private double prevRapidFireBlockerPos = -10.501;
public void setRapidFireBlockerPos(double pos){ public void setRapidFireBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor; pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevRapidFireBlockerPos){ if (pos != prevRapidFireBlockerPos){
rapidFireBlocker.setPosition(pos); rapidFireBlocker.setPosition(pos);
} }

View File

@@ -1,12 +1,19 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import static org.firstinspires.ftc.teamcode.utilsv2.Flywheel.*;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower; import com.pedropathing.follower.Follower;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
@Config
public class Shooter { public class Shooter {
Robot robot; Robot robot;
Flywheel fly;
Turret turr; Turret turr;
VelocityCommander commander; VelocityCommander commander;
@@ -14,30 +21,38 @@ public class Shooter {
double goalY = 0.0; double goalY = 0.0;
double obeliskX = 72; double obeliskX = 72;
double obeliskY = 144; double obeliskY = 144;
double turretGoalX = 0;
double turretGoalY = 0;
private boolean red = true; private boolean red = true;
public static boolean manualFlywheel = false;
Follower follow; Follower follow;
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance) { public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel, VelocityCommander com) {
this.robot = rob; this.robot = rob;
this.turr = new Turret(rob); this.fly = flywheel;
this.turr = turret;
this.follow = follower; this.follow = follower;
this.commander = new VelocityCommander(); this.commander = com;
setRedAlliance(redAlliance); setRedAlliance(redAlliance);
if (redAlliance) {
goalX = 144;
} else {
goalX = 0;
}
goalY = 144;
} }
public void setRedAlliance(boolean input) { public void setRedAlliance(boolean input) {
this.red = input; this.red = input;
if (this.red) {
goalX = 72;
turretGoalX = 68;
} else {
goalX = -72;
turretGoalX = -68;
}
goalY = 72;
turretGoalY = 68;
} }
private double flywheelVelocity = 0.0; private double flywheelVelocity = 0.0;
@@ -59,6 +74,10 @@ public class Shooter {
this.state = shooterState; this.state = shooterState;
} }
public ShooterState getState(){
return state;
}
public void setTurretPosition(double input) { public void setTurretPosition(double input) {
this.turretPosition = input; this.turretPosition = input;
} }
@@ -66,24 +85,39 @@ public class Shooter {
public void setFlywheelVelocity(double input) { public void setFlywheelVelocity(double input) {
this.flywheelVelocity = input; this.flywheelVelocity = input;
} }
public double getFlywheelVelocity(){return this.flywheelVelocity;}
public int getObeliskID() { public int getObeliskID() {
return turr.getObeliskID(); return turr.getObeliskID();
} }
private final double shooterDistFromCenter = 1.545;
public void update() { public void update(double voltage) {
setRedAlliance(Color.redAlliance);
switch (state) { switch (state) {
case NOTHING: case NOTHING:
break; break;
case MANUAL: case MANUAL:
manualFlywheel = true;
commander.getVeloPredictive(
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage,
fly.getAverageVelocity()
);
fly.manageFlywheel(flywheelVelocity);
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
turr.manual(turretPosition); turr.manual(turretPosition);
break; break;
case TRACK_GOAL: case TRACK_GOAL:
manualFlywheel = false;
turr.trackGoal( turr.trackGoal(
(follow.getPose().getX() - goalX), (turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(follow.getPose().getY() - goalY), (turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getHeading(), follow.getHeading(),
follow.getAngularVelocity(), follow.getAngularVelocity(),
follow.getVelocity().getXComponent(), follow.getVelocity().getXComponent(),
@@ -92,51 +126,71 @@ public class Shooter {
follow.getAcceleration().getYComponent() follow.getAcceleration().getYComponent()
); );
flywheelVelocity = commander.getVeloPredictive( commander.getVeloPredictive(
(follow.getPose().getX() - goalX), (goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(follow.getPose().getY() - goalY), (goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getVelocity().getXComponent(), follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent() follow.getAcceleration().getYComponent(),
voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM();
double hood1 = Math.max(0.35, Math.min(0.88, commander.getHoodPredicted() + TeleopV4.hoodOffset));
robot.setHoodPos(hood1);
fly.manageFlywheel(flywheelVelocity + TeleopV4.flywheelOffset);
fly.setF(voltage);
break; break;
case READ_OBELISK: case READ_OBELISK:
turr.trackObelisk( manualFlywheel = false;
(follow.getPose().getX() - goalX), robot.setTurretPos(Turret.neutralPosition);
(follow.getPose().getY() - goalY),
follow.getHeading()
);
flywheelVelocity = commander.getVeloPredictive( turr.detectObelisk();
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY), commander.getVeloPredictive(
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getVelocity().getXComponent(), follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent() follow.getAcceleration().getYComponent(),
voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM();
fly.manageFlywheel(0);
fly.setF(voltage);
break; break;
case MANUAL_TURRET_TRACK_FLY: case MANUAL_TURRET_TRACK_FLY:
manualFlywheel = false;
turr.manual(turretPosition); turr.manual(turretPosition);
flywheelVelocity = commander.getVeloPredictive( commander.getVeloPredictive(
(follow.getPose().getX() - goalX), (goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(follow.getPose().getY() - goalY), (goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getVelocity().getXComponent(), follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent() follow.getAcceleration().getYComponent(),
voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM();
double hood2 = Math.max(0.35, Math.min(0.88, commander.getHoodPredicted() + TeleopV4.hoodOffset));
robot.setHoodPos(hood2);
fly.manageFlywheel(flywheelVelocity + TeleopV4.flywheelOffset);
break; break;
case MANUAL_FLYWHEEL_TRACK_TURR: case MANUAL_FLYWHEEL_TRACK_TURR:
manualFlywheel = true;
turr.trackGoal( turr.trackGoal(
(follow.getPose().getX() - goalX), (turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(follow.getPose().getY() - goalY), (turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getHeading(), follow.getHeading(),
follow.getAngularVelocity(), follow.getAngularVelocity(),
follow.getVelocity().getXComponent(), follow.getVelocity().getXComponent(),
@@ -144,10 +198,26 @@ public class Shooter {
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent() follow.getAcceleration().getYComponent()
); );
commander.getVeloPredictive(
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage,
fly.getAverageVelocity()
);
fly.manageFlywheel(flywheelVelocity);
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
fly.setF(voltage);
break; break;
} }
} }
public double getDistance(){return commander.getDistance();}
} }

View File

@@ -1,11 +1,14 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PIDController;
import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.util.Range; import com.qualcomm.robotcore.util.Range;
import org.firstinspires.ftc.teamcode.constants.Color;
import java.util.List; import java.util.List;
@Config @Config
@@ -13,9 +16,22 @@ public class Turret {
Robot robot; Robot robot;
private final double servoTicksPer180 = 0.58; private final double servoTicksPer180 = 0.58;
private final double neutralPosition = 0.51; public static double neutralPosition = 0.51;
private final double turretMin = 0.05; private final double turretMin = 0.13;
private final double turretMax = 0.95; private final double turretMax = 0.87;
public static boolean limelightUsed = true;
public static double B_PID_P = 0.0001, B_PID_I = 0.0, B_PID_D = 0.000005;
LLResult result;
PIDController bearingPID;
boolean bearingAligned = false;
public int LL_COAST_TICKS = 5;
public static double TARGET_POSITION_TOLERANCE = 1.5;
public static double alphaTX = 0.3;
private double targetTx = 0;
private double currentTrackOffset = 0;
private double llCoast = 0;
private double servoAngle = 0.51;
double tx = 0.0;
private final double hVelK = 0; // TODO: Tune private final double hVelK = 0; // TODO: Tune
private final double xVelK = 0; // TODO: Tune private final double xVelK = 0; // TODO: Tune
private final double xAccK = 0; // TODO: Tune private final double xAccK = 0; // TODO: Tune
@@ -28,6 +44,7 @@ public class Turret {
public Turret(Robot rob) { public Turret(Robot rob) {
this.robot = rob; this.robot = rob;
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
} }
private double wrapAngle(double angle) { private double wrapAngle(double angle) {
@@ -36,6 +53,43 @@ public class Turret {
return angle; return angle;
} }
private void limelightRead() { // only for tracking purposes, not general reads
switchPipeline(PipelineMode.TRACKING);
result = robot.limelight.getLatestResult();
tx = 1000;
if (result != null) {
if (result.isValid()) {
tx = result.getTx();
}
}
}
public double getTX(){return tx;}
public enum PipelineMode{
OBELISK,
TRACKING
}
private int prevPipeline = 0;
public void switchPipeline(PipelineMode pipelineMode){
int pipeline = 0;
if (pipelineMode == PipelineMode.OBELISK){
pipeline = 1;
} else if (pipelineMode == PipelineMode.TRACKING){
if (Color.redAlliance){
pipeline = 4;
} else {
pipeline = 2;
}
}
if (pipeline != prevPipeline){
robot.limelight.pipelineSwitch(pipeline);
}
prevPipeline = pipeline;
}
public int pipeline(){return prevPipeline;}
public void trackObelisk(double dx, double dy, double h) { public void trackObelisk(double dx, double dy, double h) {
double heading = wrapAngle(h); double heading = wrapAngle(h);
@@ -54,7 +108,6 @@ public class Turret {
robot.setTurretPos(servoAngle); robot.setTurretPos(servoAngle);
detectObelisk(); detectObelisk();
} }
@@ -63,32 +116,26 @@ public class Turret {
return obeliskID; return obeliskID;
} }
private int detectObelisk() { public void detectObelisk() {
robot.limelight.pipelineSwitch(1); result = robot.limelight.getLatestResult();
LLResult result = robot.limelight.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) {
double currentTx = fiducial.getTargetXDegrees();
if (currentTx > prevTx){
obeliskID = fiducial.getFiducialId(); obeliskID = fiducial.getFiducialId();
} }
} }
} }
return obeliskID;
}
public void manual (double pos) { public void manual (double pos) {
robot.setTurretPos(pos); robot.setTurretPos(pos);
} }
public void trackGoal(double dx, double dy, double h, double hVel, double xVel, double xAcc, double yVel, double yAcc) { public void trackGoal(double dx, double dy, double h, double hVel, double xVel, double xAcc, double yVel, double yAcc) {
// dx, dy, dz is target - robot // dx, dy, dz is target - robot
// h is the raw heading where 0 degrees is positive x in the system of x, y // h is the raw heading where 0 degrees is positive x in the system of x, y
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D); // Keep when debugging/tuning, comment out when doing teleop
double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot
double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot
double predictedH = h + (hVel * hVelK); // Positive bc h = robot heading double predictedH = h + (hVel * hVelK); // Positive bc h = robot heading
@@ -98,11 +145,34 @@ public class Turret {
double fieldRelativeHeading = Math.atan2(predictedDy, predictedDx); double fieldRelativeHeading = Math.atan2(predictedDy, predictedDx);
double angleDelta = fieldRelativeHeading - predictedH; double angleDelta = fieldRelativeHeading - predictedH;
angleDelta = wrapAngle(angleDelta); angleDelta = wrapAngle(angleDelta) / (2.0 * Math.PI);
double servoTicksFromNeutral = (angleDelta / (2.0 * Math.PI)) * (2.0 * servoTicksPer180); double bearingOffset = 0;
if (limelightUsed && servoAngle > turretMin && servoAngle < turretMax){
limelightRead();
if (result.isValid() && tx < 100){
targetTx = (tx*alphaTX)+(targetTx*(1-alphaTX));
bearingAligned = Math.abs(targetTx) < TARGET_POSITION_TOLERANCE;
if (!bearingAligned){
bearingOffset = (bearingPID.calculate(targetTx, 0.0));
}
} else {
targetTx = 0;
bearingOffset = 0;
}
currentTrackOffset += bearingOffset;
llCoast = LL_COAST_TICKS;
} else {
if (llCoast <= 0){
currentTrackOffset = 0;
} else {
llCoast--;
}
}
double servoAngle = neutralPosition + servoTicksFromNeutral; double servoTicksFromNeutral = (angleDelta+currentTrackOffset) * (2.0 * servoTicksPer180);
servoAngle = neutralPosition + servoTicksFromNeutral;
servoAngle = Range.clip(servoAngle, turretMin, turretMax); servoAngle = Range.clip(servoAngle, turretMin, turretMax);

View File

@@ -1,34 +1,122 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config;
@Config
public class VelocityCommander { public class VelocityCommander {
private final double goalH = 20.0; //TODO: Tune public static double xVelK = 0.05; // TODO: Tune
private final double xVelK = 0; // TODO: Tune public static double xAccK = 0.025; // TODO: Tune
private final double xAccK = 0; // TODO: Tune public static double yVelK = 0.05; // TODO: Tune
private final double yVelK = 0; // TODO: Tune public static double yAccK = 0.025; // TODO: Tune
private final double yAccK = 0; // TODO: Tune public static boolean lockFront = false;
public static boolean lockBack = false;
public static int farBound = 138;
public static int closeBound = 112;
public static double errorHoodAdjustment = 0.0005;
private double hoodPos = 0.88;
private double transferPow = -1;
private int velo = 0;
public VelocityCommander() { public VelocityCommander() {}
}
final double veloA = -0.00000133612;
final double veloB = 0.000542733;
final double veloC = -0.0739531;
final double veloD = 5.16759;
final double veloE = 62.45781;
final double veloF = -0.0000833333;
final double veloG = 0.0377857;
final double veloH = -4.55067;
final double veloI = 456.97486;
private double distToRPM (double dist){ private double distToRPM (double dist){
return Math.sqrt(dist*dist + goalH*goalH); double currentVelo;
//TODO: Add regression here using goalH if (lockFront && dist > closeBound){
dist = closeBound;
} else if (lockBack && dist < farBound){
dist = farBound;
}
if (dist < 54) {
velo = 2000;
} else if (dist > 174){
velo = 3700;
} else {
currentVelo = veloA*Math.pow(dist, 4) +
veloB*Math.pow(dist, 3) +
veloC*Math.pow(dist, 2) +
veloD*Math.pow(dist, 1) +
veloE;
velo = 10 * Math.round((float) Math.max(200, Math.min(360, currentVelo)));
}
return velo;
} }
final double hoodA = 9.04203*Math.pow(10, -8);
final double hoodB = -0.0000204165;
final double hoodC = -0.00252089;
final double hoodD = 1.06154;
final double hoodE = -0.002;
final double hoodF = 0.918;
private void distToHood (double dist){
if (dist > 174){
hoodPos = 0.48;
} else if (dist < 54){
hoodPos = 0.88;
} else {
hoodPos = hoodA*Math.pow(dist, 3) +
hoodB*Math.pow(dist, 2) +
hoodC*Math.pow(dist, 1) +
hoodD;
}
if (lockBack){
hoodPos-=0.04;
}
hoodPos = Math.max(0.48, Math.min(0.88, hoodPos));
}
public double getHoodPredicted(){
return hoodPos;
}
private void distToTransferPow(double dist, double voltage){
if (dist < 140){
transferPow = -0.85;
} else {
transferPow = -0.7;
}
}
public double getTransferPow(){return transferPow;}
// 27
public double getVeloStationary (double distance){ public double getVeloStationary (double distance){
return distToRPM(distance); return distToRPM(distance);
} }
public double getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc) { double predictedDist = 0;
public void getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc, double voltage, double velocity) {
double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot
double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot
double predictedDist = Math.sqrt(dx*dx + dy*dy); double goalHeight = 28;
predictedDist = Math.sqrt(predictedDx*predictedDx + predictedDy*predictedDy + goalHeight * goalHeight);
return distToRPM(predictedDist); distToHood(predictedDist);
distToTransferPow(predictedDist, voltage);
distToRPM(predictedDist);
// hoodPos += adjustHood(predictedDist, velocity, velo);
} }
public double adjustHood(double dist, double currentVelocity, double targetVelocity){
double error = targetVelocity - currentVelocity;
if (dist < farBound || error < 0){
error = 0;
}
System.out.println("Error "+ error);
return error * errorHoodAdjustment;
}
public double getPredictedRPM(){return velo;}
public double getDistance(){return predictedDist;}
} }