70 Commits

Author SHA1 Message Date
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
e658ec044c fixed issue - two flywheel instances created a conflict 2026-06-03 10:20:13 -05:00
12e5fba938 fixed issue - two flywheel instances created a conflict 2026-06-03 10:18:13 -05:00
47c505742a fixes to flywheel in order to operate more globally 2026-06-03 10:03:34 -05:00
c8e9be1c08 Merge remote-tracking branch 'origin/danielv5' into danielv5 2026-06-03 00:22:11 -05:00
28451ce26d auto coded 2026-06-03 00:21:51 -05:00
9c3b4c2010 Add beam break sensors to Hardware_Tester 2026-06-03 00:04:20 -05:00
7665957c7a readjusted shooter test
@KeshavAnandCode please merge
2026-06-02 19:14:58 -05:00
ccc6a608fc Merge branch 'update-teleop' into danielv5 2026-06-02 18:28:00 -05:00
8eba32de94 new auto in progress 2026-06-02 18:22:41 -05:00
5c9ebf6eac some changes 2026-06-02 18:22:28 -05:00
a540d333f1 shoooooottteeer test 2026-06-02 18:12:32 -05:00
180e7629bf Added spindexer to teleopv4 2026-06-02 17:18:04 -05:00
ae25df0393 Fixed spidnexer i think 2026-06-02 17:08:26 -05:00
946deca751 middle of tuning 2026-06-02 17:04:45 -05:00
75b9b7b6b1 middle of tuning 2026-06-02 17:04:28 -05:00
1a1c99791d Made Robot Singleton 2026-06-02 16:31:33 -05:00
88cf03a230 Merge remote-tracking branch 'origin/danielv5' into update-teleop 2026-06-02 15:59:18 -05:00
82c8ebf941 umiddle of tuning 2026-06-02 15:58:49 -05:00
aabc746a2e Stash update 2026-06-02 15:57:31 -05:00
f14dc3681a setup robot confg 2026-06-02 15:41:01 -05:00
184ec893a4 Added shooter class to manager flywheel turret and targetter 2026-06-01 17:12:17 -05:00
f32f31a224 Merge remote-tracking branch 'origin/danielv5' into update-teleop 2026-06-01 16:25:07 -05:00
bfb37f13f8 added neutral shift 2026-06-01 16:24:11 -05:00
ccc0e2123a programmer to config robot 2026-06-01 16:21:48 -05:00
a470b7dbc4 loop times calling 2026-06-01 16:21:31 -05:00
dd2890ea4a Merge branch 'main' into danielv5 2026-06-01 14:44:08 -05:00
76f58308fb IGNORE THIS NEXT PUSH 2026-05-25 22:38:26 -05:00
658e8ea1d0 Added flywheel copied basically but added average velo calculations 2026-05-25 16:35:25 -07:00
9ab69f8fbe added obelisk code 2026-05-25 16:29:38 -07:00
ed970eaf38 changed to radians, accounted for velo and acc 2026-05-25 15:39:10 -07:00
e3105a339d added turretv2 starter code 2026-05-25 15:19:05 -07:00
6e31da5f1c teleopv4, added drivetrain center of mass correction and removed unused brake feature 2026-05-18 20:47:32 -05:00
4567a4117c Merge branch 'main' into danielv5 2026-05-18 19:46:41 -05:00
9502576876 Merge remote-tracking branch 'origin/danielv5' 2026-05-18 19:45:33 -05:00
a7bce4f6db Merge pull request #15 from Technical-Turbulence-FTC/danielv5
Danielv5
2026-05-18 18:53:36 -05:00
fb0df810e8 added transfer movement to class 2026-04-26 16:55:15 -05:00
2a012ea3ae added transfer movement to class 2026-04-26 16:54:54 -05:00
99216c1e80 adjusted to update quicker 2026-04-26 16:54:38 -05:00
3f2d54065f autoPathing complete 2026-04-25 22:18:54 -05:00
222b201561 fixed hood offset 2026-04-25 22:15:26 -05:00
81e0e80f62 auto in progress 2026-04-21 21:22:39 -05:00
7eebd42ea2 limelight relocalization in progress 2026-04-18 21:34:08 -05:00
2a29e8181b teleop is back up and running 2026-04-18 20:36:48 -05:00
6b092bdaeb Redid turret math to adjust to pedropathing field. 2026-04-18 00:03:07 -05:00
4cbb09e088 done tuning pedro pathing 2026-04-14 21:21:28 -05:00
a8d28928e2 tuned drive pidf and adjusted center to 0 2026-04-14 20:53:29 -05:00
f3efc132e7 tuned heading pidf and fixed dash 2026-04-14 20:26:19 -05:00
6c905f2506 ignore 2026-04-10 21:56:55 -05:00
1723f6f85d tuned translational pidf 2026-04-10 21:52:56 -05:00
6a3f65d4c5 before adding pidf constants 2026-04-10 19:53:54 -05:00
e40695b4f6 pedropathing added: tuning progress: forward and lateral velocities done 2026-04-07 20:55:53 -05:00
8f66ddc4bd Merge branch 'master' into danielv5
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java
2026-04-07 19:22:40 -05:00
08ba099d5b area code 2026-04-07 19:12:34 -05:00
7043274ebd test commit 3 2026-03-18 15:15:38 -05:00
bd05090afe test commit 2 2026-03-18 15:08:27 -05:00
369e379eb4 test comit 2026-03-18 15:05:37 -05:00
41853e9ad1 Testing new commit stattion 2026-03-09 16:42:00 -05:00
9ba5aebc8b Merge remote-tracking branch 'origin/danielv5' into danielv5 2026-02-28 12:31:01 -06:00
128637e8a1 for you @Matt 2026-02-28 12:30:36 -06:00
37dca729f0 spindex fix 2026-02-28 12:27:53 -06:00
fb9cbb1c71 some misc fixes 2026-02-28 12:08:13 -06:00
b342c98149 gate auto coded 2026-02-28 12:02:38 -06:00
6743481440 added control to spindexer speed 2026-02-28 11:31:32 -06:00
76dc6b12bf Open up SpinEqual position test. Eliminate pause after moving spindexer before going back to intake mode. 2026-02-28 02:49:50 -06:00
a1340c5388 night before regionals 2026-02-28 01:33:26 -06:00
e8d28b9e5f revert 2026-02-28 00:10:33 -06:00
f9013f4d79 stash 2026-02-27 23:34:22 -06:00
c42fce2e78 untested edits of autos 2026-02-27 19:01:33 -06:00
36 changed files with 3805 additions and 780 deletions

View File

@@ -0,0 +1,392 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
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.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.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos;
import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto12BallPedroPathing extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
// Flywheel flywheel;
// Targeting targeting;
// Targeting.Settings targetingSettings;
Follower follower;
// Turret turret;
// Spindexer spindexer;
// Servos servos;
MeasuringLoopTimes loopTimes;
// Wait Times
public static double shootTime = 2;
// Extra Variables
public static double intakePower = 0.3;
double shootX, shootY, shootH;
// Initialize path state machine
private enum PathState {
DRIVE_SHOOT0, WAIT_SHOOT0,
DRIVE_PICKUP1, PICKUP1, DRIVE_SHOOT1, WAIT_SHOOT1,
DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2,
DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3
}
PathState pathState = PathState.DRIVE_SHOOT0;
// Poses
public static double startPoseX = 112, startPoseY = 132.5, startPoseH = -90;
public static double shoot0X = 106, shoot0Y = 106, shoot0H = -40;
public static double drivePickup1X = 102, drivePickup1Y = 82, drivePickup1H = 0;
public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0;
public static double shoot1X = 86, shoot1Y = 82, shoot1H = -80;
public static double drivePickup2ControlX = 91.69828844730904, drivePickup2ControlY = 66.724457099909;
public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0;
public static double pickup2X = 132, pickup2Y = 57, pickup2H = 0;
public static double shoot2ControlX = 86, shoot2ControlY = 57;
public static double shoot2X = 86, shoot2Y = 82, shoot2H = -90;
public static double drivePickup3ControlX = 97.97800291788306, drivePickup3ControlY = 50.10765863138859;
public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0;
public static double pickup3X = 132, pickup3Y = 34.5, pickup3H = 0;
public static double shoot3ControlX = 86, shoot3ControlY = 34.5;
public static double shoot3X = 84, shoot3Y = 102, shoot3H = -90;
Pose startPose, shoot0,
drivePickup1, pickup1, shoot1,
drivePickup2Control, drivePickup2, pickup2, shoot2Control, shoot2,
drivePickup3Control, drivePickup3, pickup3, shoot3Control, shoot3;
private void initializePoses(){
startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH));
shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H));
drivePickup1 = new Pose(drivePickup1X, drivePickup1Y, Math.toRadians(drivePickup1H));
pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H));
shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H));
drivePickup2Control = new Pose(drivePickup2ControlX, drivePickup2ControlY);
drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H));
pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H));
shoot2Control = new Pose(shoot2ControlX, shoot2ControlY);
shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H));
drivePickup3Control = new Pose(drivePickup3ControlX, drivePickup3ControlY);
drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H));
pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H));
shoot3Control = new Pose(shoot3ControlX, shoot3ControlY);
shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H));
} // add poses to void
//Building Paths
PathChain startPose_shoot0,
shoot0_drivePickup1, drivePickup1_pickup1, pickup1_shoot1,
shoot1_drivePickup2, drivePickup2_pickup2, pickup2_shoot2,
shoot2_drivePickup3, drivePickup3_pickup3, pickup3_shoot3;
private void buildPaths(){
startPose_shoot0 = follower.pathBuilder()
.addPath(new BezierLine(startPose, shoot0))
.setLinearHeadingInterpolation(startPose.getHeading(), shoot0.getHeading())
.build();
shoot0_drivePickup1 = follower.pathBuilder()
.addPath(new BezierLine(shoot0, drivePickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), drivePickup1.getHeading())
.build();
drivePickup1_pickup1 = follower.pathBuilder()
.addPath(new BezierLine(drivePickup1, pickup1))
.setTangentHeadingInterpolation()
.build();
pickup1_shoot1 = follower.pathBuilder()
.addPath(new BezierLine(pickup1, shoot1))
.setLinearHeadingInterpolation(pickup1.getHeading(), shoot1.getHeading())
.build();
shoot1_drivePickup2 = follower.pathBuilder()
.addPath(new BezierCurve(shoot1, drivePickup2Control, drivePickup2))
.setLinearHeadingInterpolation(shoot1.getHeading(), drivePickup2.getHeading())
.build();
drivePickup2_pickup2 = follower.pathBuilder()
.addPath(new BezierLine(drivePickup2, pickup2))
.setConstantHeadingInterpolation(pickup2.getHeading())
.build();
pickup2_shoot2 = follower.pathBuilder()
.addPath(new BezierCurve(pickup2, shoot2Control, shoot2))
.setLinearHeadingInterpolation(pickup2.getHeading(), shoot2.getHeading())
.build();
shoot2_drivePickup3 = follower.pathBuilder()
.addPath(new BezierCurve(shoot2, drivePickup3Control, drivePickup3))
.setLinearHeadingInterpolation(shoot2.getHeading(), drivePickup3.getHeading())
.build();
drivePickup3_pickup3 = follower.pathBuilder()
.addPath(new BezierLine(drivePickup3, pickup3))
.setTangentHeadingInterpolation()
.build();
pickup3_shoot3 = follower.pathBuilder()
.addPath(new BezierCurve(pickup3, shoot3Control, shoot3))
.setLinearHeadingInterpolation(pickup3.getHeading(), shoot3.getHeading())
.build();
}
//Path State Machine
private boolean startAuto = true;
private double timeStamp = 0;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case DRIVE_SHOOT0:
if (startAuto){
follower.followPath(startPose_shoot0, true);
startAuto = false;
shootX = shoot0X;
shootY = shoot0Y;
shootH = shoot0H;
}
driveShoot(PathState.WAIT_SHOOT0, currentTime);
break;
case WAIT_SHOOT0:
waitShoot(PathState.DRIVE_PICKUP1, shoot0_drivePickup1, currentTime);
break;
case DRIVE_PICKUP1:
drivePickup(PathState.PICKUP1, drivePickup1_pickup1);
break;
case PICKUP1:
pickup(PathState.DRIVE_SHOOT1, pickup1_shoot1);
shootX = shoot1X;
shootY = shoot1Y;
shootH = shoot1H;
break;
case DRIVE_SHOOT1:
intakePowerDown(timeStamp, currentTime);
driveShoot(PathState.WAIT_SHOOT1, currentTime);
break;
case WAIT_SHOOT1:
waitShoot(PathState.DRIVE_PICKUP2, shoot1_drivePickup2, currentTime);
break;
case DRIVE_PICKUP2:
drivePickup(PathState.PICKUP2, drivePickup2_pickup2);
break;
case PICKUP2:
pickup(PathState.DRIVE_SHOOT2, pickup2_shoot2);
shootX = shoot2X;
shootY = shoot2Y;
shootH = shoot2H;
break;
case DRIVE_SHOOT2:
intakePowerDown(timeStamp, currentTime);
driveShoot(PathState.WAIT_SHOOT2, currentTime);
break;
case WAIT_SHOOT2:
waitShoot(PathState.DRIVE_PICKUP3, shoot2_drivePickup3, currentTime);
break;
case DRIVE_PICKUP3:
drivePickup(PathState.PICKUP3, drivePickup3_pickup3);
break;
case PICKUP3:
pickup(PathState.DRIVE_SHOOT3, pickup3_shoot3);
shootX = shoot3X;
shootY = shoot3Y;
shootH = shoot3H;
break;
case DRIVE_SHOOT3:
intakePowerDown(timeStamp, currentTime);
driveShoot(PathState.WAIT_SHOOT3, currentTime);
break;
case WAIT_SHOOT3:
// if (spindexer.shootAllComplete()){
// spindexer.resetSpindexer();
// TELE.addLine("Done Auto");
// }
break;
default:
break;
}
TELE.update(); // use for debugging
}
// Voids for State Machine
private void intakePowerDown(double stamp, double currentTime) {
double pow = (stamp - currentTime) / 2; // adjust denominator to see how much time to adjust
if (pow < -1) {pow = 0;}
// spindexer.setIntakePower(pow);
}
private void driveShoot(PathState nextState, double currentTime){
if (!follower.isBusy()){
pathState = nextState;
timeStamp = currentTime;
// spindexer.prepareShootAllContinous();
}
}
private void waitShoot(PathState nextState, PathChain nextPath, double currentTime) {
if (currentTime - timeStamp > shootTime) { // spindexer.shootAllComplete() ||
// spindexer.resetSpindexer();
pathState = nextState;
follower.followPath(nextPath, true);
// spindexer.setIntakePower(1);
}
}
private void drivePickup(PathState nextState, PathChain nextPath) {
if (!follower.isBusy()) {
pathState = nextState;
follower.followPath(nextPath, intakePower, false);
}
}
private void pickup(PathState nextState, PathChain nextPath) {
if (!follower.isBusy()) {
pathState = nextState;
follower.followPath(nextPath, true);
}
}
// Helps manage spindexer
private boolean driveToShoot(){
return pathState == PathState.DRIVE_SHOOT0 ||
pathState == PathState.DRIVE_SHOOT1 ||
pathState == PathState.DRIVE_SHOOT2 ||
pathState == PathState.DRIVE_SHOOT3;
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return (144-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());
// flywheel = new Flywheel(hardwareMap);
// targeting = new Targeting();
// targetingSettings = new Targeting.Settings(0,0);
follower = Constants.createFollower(hardwareMap);
follower.setStartingPose(new Pose(72,72,0));
// turret = new Turret(robot, TELE, robot.limelight);
// spindexer = new Spindexer(hardwareMap);
// servos = new Servos(hardwareMap);
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
// robot.light.setPosition(Color.LightRed);
boolean initializeRobot = false;
while (opModeInInit()){
follower.update();
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
// if (Color.redAlliance){
// robot.light.setPosition(Color.LightRed);
// } else {
// robot.light.setPosition(Color.LightBlue);
// }
double[] xPoses = {startPoseX, shoot0X,
drivePickup1X, pickup1X, shoot1X,
drivePickup2ControlX, drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
drivePickup3ControlX, drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
double[] headings = {startPoseH, shoot0H,
drivePickup1H, pickup1H, 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 < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
// turret.setTurret(turrDefault);
// servos.setSpinPos(spinStartPos);
}
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.update();
}
waitForStart();
if (isStopRequested()) return;
// robot.transfer.setPower(1);
limelightUsed = false;
while (opModeIsActive()){
follower.update();
pathStateMachine();
Pose currentPose = follower.getPose();
// teleStartPoseX = currentPose.getX();
// teleStartPoseY = currentPose.getY();
// teleStartPoseH = Math.toDegrees(currentPose.getHeading());
//
// turret.trackGoal(new Pose(shootX, shootY, Math.toRadians(shootH)));
// targetingSettings = targeting.calculateSettings(shootX, shootY, Math.toRadians(shootH), 0, turretInterpolate);
//
// double voltage = robot.voltage.getVoltage();
// flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
// flywheel.manageFlywheel(targetingSettings.flywheelRPM);
// servos.setHoodPos(targetingSettings.hoodAngle);
//
// if (driveToShoot()){servos.setSpinPos(spinStartPos);}
// else {spindexer.processIntake();}
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:", currentPose.getX());
TELE.addData("Y:", currentPose.getY());
TELE.addData("H:", currentPose.getHeading());
TELE.update();
}
}
}

View File

@@ -0,0 +1,366 @@
package org.firstinspires.ftc.teamcode.autonomous;
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.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.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
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;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto12Ball_Back_Sorted extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
// Wait Times
public static double shootTime = 2;
public static double openGateTime = 1.5;
// Extra Variables
public static double intakePower = 0.3;
double shootX, shootY, shootH;
// Initialize path state machine
private enum PathState {
PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0,
PICKUP1, DRIVE_OPENGATE, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1,
DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2,
DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3
}
PathState pathState = PathState.PUSHBOT;
// Poses
public static double startPoseX = 84, startPoseY = 7, startPoseH = 90;
public static double pushBotX = 94, pushBotY = 9, pushBotH = 100;
public static double shoot0ControlX = 88.29667812142038, shoot0ControlY = 52.03493699885454;
public static double shoot0X = 91, shoot0Y = 80, shoot0H = 0;
public static double pickup1ControlX = 109.29381443298968, pickup1ControlY = 82.70618556701031;
public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0;
public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165;
public static double openGateX = 129, openGateY = 74, openGateH = 0;
public static double shoot1ControlX = 112, shoot1ControlY = 75;
public static double shoot1X = 91, shoot1Y = 80, shoot1H = -12;
public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0;
public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0;
public static double shoot2ControlX = 102, shoot2ControlY = 63;
public static double shoot2X = 91, shoot2Y = 80, shoot2H = -50;
public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0;
public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0;
public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446;
public static double shoot3X = 84, shoot3Y = 105, shoot3H = -80;
Pose startPose, pushBot, shoot0Control, shoot0,
pickup1Control, pickup1, openGateControl, openGate, shoot1Control, shoot1,
drivePickup2, pickup2, shoot2Control, shoot2,
drivePickup3, pickup3, shoot3Control, shoot3;
private void initializePoses(){
startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH));
pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH));
shoot0Control = new Pose(shoot0ControlX, shoot0ControlY);
shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H));
pickup1Control = new Pose(pickup1ControlX, pickup1ControlY);
pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H));
openGateControl = new Pose(openGateControlX, openGateControlY);
openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH));
shoot1Control = new Pose(shoot1ControlX, shoot1ControlY);
shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H));
drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H));
pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H));
shoot2Control = new Pose(shoot2ControlX, shoot2ControlY);
shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H));
drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H));
pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H));
shoot3Control = new Pose(shoot3ControlX, shoot3ControlY);
shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H));
}
//Building Paths
PathChain startPose_pushBot, pushBot_shoot0,
shoot0_pickup1, pickup1_openGate, openGate_shoot1,
shoot1_drivePickup2, drivePickup2_pickup2, pickup2_shoot2,
shoot2_drivePickup3, drivePickup3_pickup3, pickup3_shoot3;
private void buildPaths(){
startPose_pushBot = follower.pathBuilder()
.addPath(new BezierLine(startPose, pushBot))
.setLinearHeadingInterpolation(startPose.getHeading(), pushBot.getHeading())
.build();
pushBot_shoot0 = follower.pathBuilder()
.addPath(new BezierCurve(pushBot, shoot0Control, shoot0))
.setLinearHeadingInterpolation(pushBot.getHeading(), shoot0.getHeading())
.build();
shoot0_pickup1 = follower.pathBuilder()
.addPath(new BezierCurve(shoot0, pickup1Control, pickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
.build();
pickup1_openGate = follower.pathBuilder()
.addPath(new BezierCurve(pickup1, openGateControl, openGate))
.setLinearHeadingInterpolation(pickup1.getHeading(), openGate.getHeading())
.build();
openGate_shoot1 = follower.pathBuilder()
.addPath(new BezierCurve(openGate, shoot1Control, shoot1))
.setLinearHeadingInterpolation(openGate.getHeading(), shoot1.getHeading())
.build();
shoot1_drivePickup2 = follower.pathBuilder()
.addPath(new BezierLine(shoot1, drivePickup2))
.setLinearHeadingInterpolation(shoot1.getHeading(), drivePickup2.getHeading())
.build();
drivePickup2_pickup2 = follower.pathBuilder()
.addPath(new BezierLine(drivePickup2, pickup2))
.setLinearHeadingInterpolation(drivePickup2.getHeading(), pickup2.getHeading())
.build();
pickup2_shoot2 = follower.pathBuilder()
.addPath(new BezierCurve(pickup2, shoot2Control, shoot2))
.setLinearHeadingInterpolation(pickup2.getHeading(), shoot2.getHeading())
.build();
shoot2_drivePickup3 = follower.pathBuilder()
.addPath(new BezierLine(shoot2, drivePickup3))
.setLinearHeadingInterpolation(shoot2.getHeading(), drivePickup3.getHeading())
.build();
drivePickup3_pickup3 = follower.pathBuilder()
.addPath(new BezierLine(drivePickup3, pickup3))
.setLinearHeadingInterpolation(drivePickup3.getHeading(), pickup3.getHeading())
.build();
pickup3_shoot3 = follower.pathBuilder()
.addPath(new BezierCurve(pickup3, shoot3Control, shoot3))
.setLinearHeadingInterpolation(pickup3.getHeading(), shoot3.getHeading())
.build();
}
//Path State Machine
private boolean startAuto = true;
private double timeStamp = 0;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case PUSHBOT:
if (startAuto){
follower.followPath(startPose_pushBot, true);
startAuto = false;
shootX = shoot0X;
shootY = shoot0Y;
shootH = shoot0H;
}
if (!follower.isBusy()){
follower.followPath(pushBot_shoot0, true);
pathState = PathState.DRIVE_SHOOT0;
}
break;
case DRIVE_SHOOT0:
if (!follower.isBusy()){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > shootTime){
follower.followPath(shoot0_pickup1, intakePower, false);
pathState = PathState.PICKUP1;
}
break;
case PICKUP1:
if (!follower.isBusy()){
follower.followPath(pickup1_openGate, true);
pathState = PathState.OPENGATE;
shootX = shoot1X;
shootY = shoot1Y;
shootH = shoot1H;
}
break;
case DRIVE_OPENGATE:
if (!follower.isBusy()){
pathState = PathState.OPENGATE;
timeStamp = currentTime;
}
break;
case OPENGATE:
if (currentTime - timeStamp > openGateTime){
follower.followPath(openGate_shoot1, true);
pathState = PathState.DRIVE_SHOOT1;
}
break;
case DRIVE_SHOOT1:
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT1;
timeStamp = currentTime;
}
break;
case WAIT_SHOOT1:
if (currentTime - timeStamp > shootTime){
follower.followPath(shoot1_drivePickup2, true);
pathState = PathState.DRIVE_PICKUP2;
}
break;
case DRIVE_PICKUP2:
if (!follower.isBusy()) {
follower.followPath(drivePickup2_pickup2, intakePower, false);
pathState = PathState.PICKUP2;
}
break;
case PICKUP2:
if (!follower.isBusy()){
follower.followPath(pickup2_shoot2, true);
pathState = PathState.DRIVE_SHOOT2;
}
shootX = shoot2X;
shootY = shoot2Y;
shootH = shoot2H;
break;
case DRIVE_SHOOT2:
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT2;
timeStamp = currentTime;
}
break;
case WAIT_SHOOT2:
if (currentTime - timeStamp > shootTime){
follower.followPath(shoot2_drivePickup3, true);
pathState = PathState.DRIVE_PICKUP3;
}
break;
case DRIVE_PICKUP3:
if (!follower.isBusy()){
follower.followPath(drivePickup3_pickup3, intakePower, false);
pathState = PathState.PICKUP3;
}
break;
case PICKUP3:
if (!follower.isBusy()){
follower.followPath(pickup3_shoot3, true);
pathState = PathState.DRIVE_SHOOT3;
}
shootX = shoot3X;
shootY = shoot3Y;
shootH = shoot3H;
break;
case DRIVE_SHOOT3:
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT3;
}
break;
case WAIT_SHOOT3:
// 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 (144-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);
follower.setStartingPose(new Pose(72,72,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
boolean initializeRobot = false;
while (opModeInInit()){
follower.update();
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
pickup1ControlX, pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
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 < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
}
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.update();
}
waitForStart();
if (isStopRequested()) return;
limelightUsed = false;
while (opModeIsActive()){
follower.update();
pathStateMachine();
Pose currentPose = follower.getPose();
teleStartPoseX = currentPose.getX();
teleStartPoseY = currentPose.getY();
teleStartPoseH = Math.toDegrees(currentPose.getHeading());
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:", currentPose.getX());
TELE.addData("Y:", currentPose.getY());
TELE.addData("H:", currentPose.getHeading());
TELE.update();
}
}
}

View File

@@ -2,6 +2,7 @@ package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.*;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos0;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos3;
@@ -19,6 +20,7 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferSe
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.FtcDashboard;
@@ -89,10 +91,6 @@ public class Auto_LT_Close extends LinearOpMode {
public static double intake1GateTime = 3.3;
public static double lastShootTime = 27;
public static double openGateX = 26;
public static double openGateY = 48;
public static double openGateH = Math.toRadians(155);
Robot robot;
MultipleTelemetry TELE;
MecanumDrive drive;
@@ -124,6 +122,8 @@ public class Auto_LT_Close extends LinearOpMode {
double xShootGate, yShootGate, hShootGate;
double xLeave, yLeave, hLeave;
double xLeaveGate, yLeaveGate, hLeaveGate;
double openGateCloseX = 0, openGateCloseY = 0, openGateCloseH = 0;
double openGateMiddleX = 0, openGateMiddleY = 0, openGateMiddleH = 0;
int ballCycles = 3;
int prevMotif = 0;
@@ -134,6 +134,7 @@ public class Auto_LT_Close extends LinearOpMode {
double obeliskTurrPos3 = 0.0;
double waitToPickupGate = 0;
double obeliskTurrPosAutoStart = 0;
boolean limelightStart = false;
// initialize path variables here
TrajectoryActionBuilder shoot0 = null;
@@ -179,13 +180,14 @@ public class Auto_LT_Close extends LinearOpMode {
servos.setTransferPos(transferServo_out);
limelightUsed = false;
// Spindexer.teleop = false;
robot.light.setPosition(1);
hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint").resetPosAndIMU();
while (opModeInInit()) {
if (limelightUsed && !gateCycle){
if (limelightUsed && !gateCycle && limelightStart){
Actions.runBlocking(
autoActions.detectObelisk(
0.1,
@@ -207,14 +209,6 @@ public class Auto_LT_Close extends LinearOpMode {
}
}
if (!gateCycle) {
turret.pipelineSwitch(1);
} else if (redAlliance) {
turret.pipelineSwitch(4);
} else {
turret.pipelineSwitch(2);
}
if (gateCycle) {
servos.setHoodPos(hoodGate0Start);
} else {
@@ -249,8 +243,10 @@ public class Auto_LT_Close extends LinearOpMode {
if (gamepad2.squareWasPressed()) {
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
sleep(100);
robot.limelight.start();
limelightUsed = true;
limelightStart = true;
gamepad2.rumble(500);
}
@@ -258,6 +254,12 @@ public class Auto_LT_Close extends LinearOpMode {
if (redAlliance) {
robot.light.setPosition(0.28);
if (gateCycle){
turret.pipelineSwitch(1);
} else {
turret.pipelineSwitch(4);
}
// ---- FIRST SHOT ----
x1 = rx1;
y1 = ry1;
@@ -307,6 +309,14 @@ public class Auto_LT_Close extends LinearOpMode {
pickupGateBY = rPickupGateBY;
pickupGateBH = rPickupGateBH;
openGateCloseX = rOpenGateCloseX;
openGateCloseY = rOpenGateCloseY;
openGateCloseH = rOpenGateCloseH;
openGateMiddleX = rOpenGateMiddleX;
openGateMiddleY = rOpenGateMiddleY;
openGateMiddleH = rOpenGateMiddleH;
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
@@ -314,6 +324,12 @@ public class Auto_LT_Close extends LinearOpMode {
} else {
robot.light.setPosition(0.6);
if (gateCycle){
turret.pipelineSwitch(5);
} else {
turret.pipelineSwitch(2);
}
// ---- FIRST SHOT ----
x1 = bx1;
y1 = by1;
@@ -363,25 +379,34 @@ public class Auto_LT_Close extends LinearOpMode {
pickupGateBY = bPickupGateBY;
pickupGateBH = bPickupGateBH;
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
openGateCloseX = bOpenGateCloseX;
openGateCloseY = bOpenGateCloseY;
openGateCloseH = bOpenGateCloseH;
openGateMiddleX = bOpenGateMiddleX;
openGateMiddleY = bOpenGateMiddleY;
openGateMiddleH = bOpenGateMiddleH;
obeliskTurrPosAutoStart = turrDefault + blueObeliskTurrPos0;
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
}
if (gateCycle) {
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
.strafeToLinearHeading(new Vector2d(xShoot0, yShoot0), Math.toRadians(hShoot0));
} else {
// if (gateCycle) {
// shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
// .strafeToLinearHeading(new Vector2d(xShoot0, yShoot0), Math.toRadians(hShoot0));
// } else {
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
.strafeToLinearHeading(new Vector2d(x1, y1), Math.toRadians(h1));
}
// }
if (gateCycle) {
pickup2 = shoot0.endTrajectory().fresh()
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
.strafeToLinearHeading(new Vector2d(x3b, y3b), Math.toRadians(h3b),
new TranslationalVelConstraint(pickupStackGateSpeed));
new TranslationalVelConstraint(pickupStackGateSpeed))
.strafeToLinearHeading(new Vector2d(openGateMiddleX, openGateMiddleY), Math.toRadians(openGateMiddleH));
} else {
pickup2 = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
@@ -389,13 +414,14 @@ public class Auto_LT_Close extends LinearOpMode {
new TranslationalVelConstraint(pickup1Speed));
}
if (gateCycle&& withPartner) {
// if (gateCycle && withPartner) {
// shoot2 = pickup2.endTrajectory().fresh()
// .strafeToLinearHeading(new Vector2d(openGateX, openGateY), Math.toRadians(openGateH))
// .strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(pickupGateAH));
// } else
if (gateCycle) {
shoot2 = pickup2.endTrajectory().fresh()
.strafeToLinearHeading(new Vector2d(openGateX, openGateY), Math.toRadians(openGateH))
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(pickupGateAH));
} else if (gateCycle) {
shoot2 = pickup2.endTrajectory().fresh()
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(hShootGate));
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
} else if (ballCycles < 3) {
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
@@ -417,10 +443,11 @@ public class Auto_LT_Close extends LinearOpMode {
if (gateCycle) {
pickup1 = gateCycleShoot.endTrajectory().fresh()
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, Math.toRadians(h1)))
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
new TranslationalVelConstraint(pickupStackGateSpeed));
new TranslationalVelConstraint(pickupStackGateSpeed))
.strafeToLinearHeading(new Vector2d(openGateCloseX, openGateCloseY), Math.toRadians(openGateCloseH));
} else {
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, Math.toRadians(h1)))
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
@@ -431,7 +458,7 @@ public class Auto_LT_Close extends LinearOpMode {
if (gateCycle) {
shoot1 = pickup1.endTrajectory().fresh()
.strafeToLinearHeading(new Vector2d(xLeaveGate, yLeaveGate), Math.toRadians(hLeaveGate));
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
} else if (ballCycles < 2) {
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, Math.toRadians(h2b)))
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
@@ -477,30 +504,13 @@ public class Auto_LT_Close extends LinearOpMode {
if (gateCycle) {
startAutoGate();
startAuto();
shoot(0.501, 0.501, 0.501);
cycleStackMiddleGate();
cycleStackClose();
shoot(0.501,0.501, 0.501);
while (getRuntime() - stamp < endGateTime) {
cycleGateIntake();
if (getRuntime() - stamp < lastShootTime) {
cycleGateShoot();
cycleStackMiddle();
shoot(0.501, 0.501, 0.501);
}
}
cycleStackCloseIntakeGate();
if (getRuntime() - stamp < lastShootTime) {
cycleStackCloseShootGate();
}
shoot(0.501, 0.501, 0.501);
} else {
startAuto();
shoot(0.501, 0.501,0.501);

View File

@@ -1,6 +1,11 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.*;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.bStackPickupFarAH;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.bStackPickupFarAY;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.bStackPickupFarBH;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.bStackPickupFarBX;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.bStackPickupFarBY;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos1;
@@ -63,8 +68,8 @@ public class Auto_LT_Far extends LinearOpMode {
boolean stack3 = true;
double xStackPickupA, yStackPickupA, hStackPickupA;
double xStackPickupB, yStackPickupB, hStackPickupB;
public static int pickupStackSpeed = 17;
public static int pickupGateSpeed = 25;
public static int pickupStackSpeed = 12;
public static int pickupGateSpeed = 30;
int prevMotif = 0;
public static double spindexerSpeedIncrease = 0.014;
public static double shootAllTime = 2;
@@ -74,8 +79,8 @@ public class Auto_LT_Far extends LinearOpMode {
public static double shootStackTime = 2;
public static double shootGateTime = 2.5;
public static double colorSenseTime = 1;
public static double intakeStackTime = 4.5;
public static double intakeGateTime = 8;
public static double intakeStackTime = 5;
public static double intakeGateTime = 3.75;
double obeliskTurrPos1 = 0.0;
double obeliskTurrPos2 = 0.0;
double obeliskTurrPos3 = 0.0;
@@ -117,12 +122,10 @@ public class Auto_LT_Far extends LinearOpMode {
robot.limelight.pipelineSwitch(1);
turret = new Turret(robot, TELE, robot.limelight);
limelightUsed = false;
turret.setTurret(turrDefault);
servos.setSpinPos(spinStartPos);
servos.setTransferPos(transferServo_out);
// Spindexer.teleop = false;
while (opModeInInit()) {
@@ -164,17 +167,17 @@ public class Auto_LT_Far extends LinearOpMode {
yShoot = rShootY;
hShoot = rShootH;
xStackPickupA = rStackPickupAX;
yStackPickupA = rStackPickupAY;
hStackPickupA = rStackPickupAH;
xStackPickupA = rStackPickupFarAX;
yStackPickupA = rStackPickupFarAY;
hStackPickupA = rStackPickupFarAH;
xStackPickupB = rStackPickupBX;
yStackPickupB = rStackPickupBY;
hStackPickupB = rStackPickupBH;
xStackPickupB = rStackPickupFarBX;
yStackPickupB = rStackPickupFarBY;
hStackPickupB = rStackPickupFarBH;
pickupGateX = rPickupGateX;
pickupGateY = rPickupGateY;
pickupGateH = rPickupGateH;
pickupGateX = rPickupGateXA;
pickupGateY = rPickupGateYA;
pickupGateH = rPickupGateHA;
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
@@ -184,9 +187,14 @@ public class Auto_LT_Far extends LinearOpMode {
if (gamepad2.squareWasPressed()){
turret.pipelineSwitch(4);
robot.limelight.start();
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
gamepad2.rumble(500);
sleep(1000);
turret.setTurret(turrDefault);
servos.setSpinPos(spinStartPos);
limelightUsed = true;
servos.setTransferPos(transferServo_out);
}
} else {
robot.light.setPosition(0.6);
@@ -203,17 +211,17 @@ public class Auto_LT_Far extends LinearOpMode {
yShoot = bShootY;
hShoot = bShootH;
xStackPickupA = bStackPickupAX;
yStackPickupA = bStackPickupAY;
hStackPickupA = bStackPickupAH;
xStackPickupA = bStackPickupFarAX;
yStackPickupA = bStackPickupFarAY;
hStackPickupA = bStackPickupFarAH;
xStackPickupB = bStackPickupBX;
yStackPickupB = bStackPickupBY;
hStackPickupB = bStackPickupBH;
xStackPickupB = bStackPickupFarBX;
yStackPickupB = bStackPickupFarBY;
hStackPickupB = bStackPickupFarBH;
pickupGateX = bPickupGateX;
pickupGateY = bPickupGateY;
pickupGateH = bPickupGateH;
pickupGateX = bPickupGateXA;
pickupGateY = bPickupGateYA;
pickupGateH = bPickupGateHA;
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
@@ -223,9 +231,14 @@ public class Auto_LT_Far extends LinearOpMode {
if (gamepad2.squareWasPressed()){
turret.pipelineSwitch(2);
robot.limelight.start();
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
gamepad2.rumble(500);
sleep(1000);
turret.setTurret(turrDefault);
limelightUsed = true;
servos.setSpinPos(spinStartPos);
servos.setTransferPos(transferServo_out);
}
}
@@ -244,19 +257,16 @@ public class Auto_LT_Far extends LinearOpMode {
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
pickupGate = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
.strafeToLinearHeading(new Vector2d(pickupGateX, pickupGateY), Math.toRadians(pickupGateH))
.waitSeconds(0.2)
.strafeToLinearHeading(new Vector2d(pickupGateXB, pickupGateYB), Math.toRadians(pickupGateHB))
.strafeToLinearHeading(new Vector2d(pickupGateXC, pickupGateYC), Math.toRadians(pickupGateHC),
.strafeToLinearHeading(new Vector2d(pickupGateX, pickupGateY), Math.toRadians(pickupGateH),
new TranslationalVelConstraint(pickupGateSpeed));
shootGate = drive.actionBuilder(new Pose2d(pickupGateX, pickupGateY, Math.toRadians(pickupGateH)))
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
limelightUsed = true;
TELE.addData("Red?", redAlliance);
TELE.addData("Turret Default", turrDefault);
TELE.addData("Limelight On?",limelightUsed);
TELE.addData("Gate Cycle?", gatePickup);
TELE.addData("Pickup Stack?", stack3);
TELE.addData("Start Position", autoStart);
@@ -275,11 +285,17 @@ public class Auto_LT_Far extends LinearOpMode {
robot.transfer.setPower(1);
startAuto();
shoot();
if (redAlliance){
shoot(autoStartRX, autoStartRY, autoStartRH);
} else {
shoot(autoStartBX, autoStartBY, autoStartBH);
}
if (stack3){
cycleStackFar();
shoot();
shoot(xShoot, yShoot, hShoot);
}
while (gatePickup && getRuntime() - stamp < endAutoTime){
@@ -288,10 +304,7 @@ public class Auto_LT_Far extends LinearOpMode {
break;
}
cycleGatePrepareShoot();
if (getRuntime() - stamp > endAutoTime + shootAllTime + 1){
break;
}
shoot();
shoot(xShoot, yShoot, hShoot);
}
if (gatePickup || stack3){
@@ -318,28 +331,46 @@ public class Auto_LT_Far extends LinearOpMode {
}
void shoot(){
void shoot(double x, double y, double z){
Actions.runBlocking(
new ParallelAction(
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, 0.501, 0.501, 0.501)
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, x, y, z)
)
);
}
void startAuto(){
if (redAlliance){
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
flywheel0Time,
0.501,
0.501,
0.501,
autoStartRX,
autoStartRY,
autoStartRH,
true
)
)
);
} else {
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
flywheel0Time,
autoStartBX,
autoStartBY,
autoStartBH,
true
)
)
);
}
}
void leave3Ball(){
@@ -361,34 +392,17 @@ public class Auto_LT_Far extends LinearOpMode {
xStackPickupB,
yStackPickupB,
hStackPickupB
),
autoActions.detectObelisk(
intakeStackTime,
xStackPickupB,
yStackPickupB,
posXTolerance,
posYTolerance,
obeliskTurrPos3
)
)
);
motif = turret.getObeliskID();
if (motif == 0) motif = 22;
prevMotif = motif;
servos.setSpinPos(spinStartPos);
spindexer.setIntakePower(-0.1);
Actions.runBlocking(
new ParallelAction(
shoot3.build(),
autoActions.prepareShootAll(
colorSenseTime,
shootStackTime,
motif,
xShoot,
yShoot,
hShoot)
autoActions.manageShooterAuto(
shootStackTime,xShoot, yShoot, hShoot, false
)
)
);
}
@@ -398,39 +412,26 @@ public class Auto_LT_Far extends LinearOpMode {
new ParallelAction(
pickupGate.build(),
autoActions.intake(
intakeStackTime,
pickupGateX,
pickupGateY,
pickupGateH
),
autoActions.detectObelisk(
intakeGateTime,
pickupGateX,
pickupGateY,
posXTolerance,
posYTolerance,
obeliskTurrPos3
pickupGateH
)
)
);
motif = turret.getObeliskID();
if (motif == 0) motif = prevMotif;
prevMotif = motif;
}
void cycleGatePrepareShoot(){
spindexer.setIntakePower(-0.1);
Actions.runBlocking(
new ParallelAction(
shootGate.build(),
autoActions.prepareShootAll(
colorSenseTime,
autoActions.manageShooterAuto(
shootGateTime,
motif,
xShoot,
yShoot,
hShoot
hShoot,
false
)
)
);

View File

@@ -18,6 +18,8 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.Pose2d;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@@ -54,8 +56,8 @@ public class AutoActions {
public static double firstSpindexShootPos = spinStartPos;
private boolean shootForward = true;
public int motif = 0;
double spinEndPos = ServoPositions.spinEndPos;
double spinEndPos = 0.95;
private boolean intaking = false;
public AutoActions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur, Light lig) {
this.robot = rob;
this.drive = dri;
@@ -427,8 +429,10 @@ public class AutoActions {
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
servos.setSpinPos(spindexer_intakePos1);
intaking = false;
return false;
} else {
intaking = true;
return true;
}
}
@@ -523,7 +527,7 @@ public class AutoActions {
drive.updatePoseEstimate();
Pose2d currentPose = drive.localizer.getPose();
Pose2d currentPose = null; //drive.localizer.getPose();
if (ticker == 0) {
stamp = System.currentTimeMillis();
@@ -540,10 +544,10 @@ public class AutoActions {
ticker++;
double robotX = currentPose.position.x;
double robotY = currentPose.position.y;
double robotX = 0.0;//currentPose.position.x;
double robotY = 0.0;//currentPose.position.y;
double robotHeading = currentPose.heading.toDouble();
double robotHeading = 0.0;//currentPose.heading.toDouble();
double goalX = -15;
double goalY = 0;
@@ -552,11 +556,11 @@ public class AutoActions {
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose;
Pose deltaPose;
if (posX != 0.501) {
deltaPose = new Pose2d(posX, posY, Math.toRadians(posH));
deltaPose = new Pose(posX, posY, Math.toRadians(posH));
} else {
deltaPose = new Pose2d(dx, dy, robotHeading);
deltaPose = new Pose(dx, dy, robotHeading);
}
Turret.limelightUsed = true;
@@ -644,9 +648,9 @@ public class AutoActions {
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose;
Pose deltaPose;
if (turr == 0.501) {
deltaPose = new Pose2d(dx, dy, robotHeading);
deltaPose = new Pose(dx, dy, robotHeading);
if (!detectingObelisk) {
turret.trackGoal(deltaPose);
}
@@ -672,6 +676,44 @@ public class AutoActions {
}
};
}
public Action ShakeDrivetrain(
double time
){
return new Action() {
int ticker = 0;
double stamp = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0){
stamp = System.currentTimeMillis();
}
ticker++;
double currentStamp = System.currentTimeMillis();
if (currentStamp - stamp < time*1000 && (intaking || ticker < 50)) {
if (ticker % 10000 < 5000) {
robot.frontLeft.setPower(0.5);
robot.backLeft.setPower(0.5);
robot.frontRight.setPower(0.5);
robot.backRight.setPower(0.5);
} else {
robot.frontLeft.setPower(-0.5);
robot.backLeft.setPower(-0.5);
robot.frontRight.setPower(-0.5);
robot.backRight.setPower(-0.5);
}
return true;
} else {
robot.frontLeft.setPower(0);
robot.backLeft.setPower(0);
robot.frontRight.setPower(0);
robot.backRight.setPower(0);
return false;
}
}
};
}
}

View File

@@ -72,6 +72,7 @@ import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
@@ -489,7 +490,7 @@ public class Auto_LT_Close_12Ball extends LinearOpMode {
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
Pose deltaPose = new Pose(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);

View File

@@ -77,6 +77,7 @@ import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
@@ -628,7 +629,7 @@ public class Auto_LT_Close_GateOpen extends LinearOpMode {
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
Pose deltaPose = new Pose(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);

View File

@@ -7,23 +7,29 @@ public class Back_Poses {
public static double rLeaveX = 90, rLeaveY = 50, rLeaveH = 50.1;
public static double bLeaveX = 90, bLeaveY = -50, bLeaveH = -50;
public static double rShootX = 100, rShootY = 55, rShootH = 90;
public static double bShootX = 100, bShootY = -55, bShootH = -90;
public static double rShootX = 100, rShootY = 60, rShootH = 125.2;
public static double bShootX = 100, bShootY = -60, bShootH = -125.2;
public static double rStackPickupAX = 73, rStackPickupAY = 51, rStackPickupAH = 140;
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
public static double rStackPickupFarAX = 75, rStackPickupFarAY = 45, rStackPickupFarAH = 150;
public static double bStackPickupFarAX = 75, bStackPickupFarAY = -45, bStackPickupFarAH = -150;
public static double rStackPickupBX = 53, rStackPickupBY = 71, rStackPickupBH = 140.1;
public static double bStackPickupBX = 55, bStackPickupBY = -73, bStackPickupBH = -140.1;
public static double rStackPickupFarBX = 45, rStackPickupFarBY = 80, rStackPickupFarBH = 145.1;
public static double bStackPickupFarBX = 45, bStackPickupFarBY = -80, bStackPickupFarBH = -145.1;
public static double rPickupGateX = 50, rPickupGateY = 83, rPickupGateH = 140;
public static double bPickupGateX = 70, bPickupGateY = -90, bPickupGateH = -140;
public static double pickupGateXB = 84, pickupGateYB = 76, pickupGateHB = 140;
public static double pickupGateXC = 50, pickupGateYC = 83, pickupGateHC = 190;
public static double rStackPickupMiddleAX = 55, rStackPickupMiddleAY = 39, rStackPickupMiddleAH = 145;
public static double bStackPickupMiddleAX = 55, bStackPickupMiddleAY = -39, bStackPickupMiddleAH = -145;
public static double rStackPickupMiddleBX = 45, rStackPickupMiddleBY = 49, rStackPickupMiddleBH = 145.1;
public static double bStackPickupMiddleBX = 45, bStackPickupMiddleBY = -49, bStackPickupMiddleBH = -145.1;
public static double rPickupGateXA = 60, rPickupGateYA = 90, rPickupGateHA = 140;
public static double bPickupGateXA = 60, bPickupGateYA = -90, bPickupGateHA = -140;
public static double rPickupGateXB = 84, rPickupGateYB = 76, rPickupGateHB = 145;
public static double bPickupGateXB = 84, bPickupGateYB = -76, bPickupGateHB = -145;
public static double rPickupGateXC = 50, rPickupGateYC = 83, rPickupGateHC = 190;
public static double bPickupGateXC = 50, bPickupGateYC = -83, bPickupGateHC = -190;
public static double autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 50;
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -50;
public static double autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 54;
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -54;
}

View File

@@ -7,14 +7,14 @@ import com.acmerobotics.roadrunner.Pose2d;
public class Front_Poses {
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
public static double bx1 = 20, by1 = -0.5, bh1 = -0.1;
public static double rx1 = 30, ry1 = 5, rh1 = 0.1;
public static double bx1 = 30, by1 = -5, bh1 = -0.1;
public static double rx2a = 41, ry2a = 18, rh2a = 140;
public static double bx2a = 41, by2a = -18, bh2a = -140;
public static double rx2b = 21, ry2b = 34, rh2b = 140.1;
public static double bx2b = 23, by2b = -36, bh2b = -140.1;
public static double bx2b = 23, by2b = -34, bh2b = -140.1;
public static double rx3a = 55, ry3a = 39, rh3a = 140;
public static double bx3a = 55, by3a = -39, bh3a = -140;
@@ -33,8 +33,8 @@ public class Front_Poses {
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
public static double rShootX = 40, rShootY = 10, rShootH = 50;
public static double bShootX = 40, bShootY = -10, bShootH = -50;
public static double rShootX = 60, rShootY = 10, rShootH = 50;
public static double bShootX = 60, bShootY = -10, bShootH = -50;
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
@@ -58,5 +58,14 @@ public class Front_Poses {
public static double bPickupGateBX = 38, bPickupGateBY = -68, bPickupGateBH = -180;
public static double pickupGateCX = 34, pickupGateCY = 58, pickupGateCH = 220;
public static double rOpenGateCloseX = 20, rOpenGateCloseY = 35, rOpenGateCloseH = 230;
public static double bOpenGateCloseX = 20, bOpenGateCloseY = -35, bOpenGateCloseH = -230;
public static double rOpenGateMiddleX = 36, rOpenGateMiddleY = 59, rOpenGateMiddleH = 50;
public static double bOpenGateMiddleX = 36, bOpenGateMiddleY = -59, bOpenGateMiddleH = -50;
public static Pose2d teleStart = new Pose2d(0, 0, 0);
//For PedroPathing TODO: figure out how to change start poses in auto
public static double teleStartPoseX = 72, teleStartPoseY = 72, teleStartPoseH = 0;
}

View File

@@ -5,29 +5,42 @@ import com.acmerobotics.dashboard.config.Config;
@Config
public class ServoPositions {
public static double rapidFireBlocker_Closed = 0.35;
public static double rapidFireBlocker_Open = 0.5;
public static double spindexBlocker_Closed = 0.31;
public static double spindexBlocker_Open = 0.5;
public static double spindexer_A1 = 0.16;
public static double spindexer_A2 = 0.35;
public static double spindexer_A3 = 0.54;
public static double spindexer_B1 = 0.73;
public static double spindexer_B2 = 0.92;
public static double spindexer_intakePos1 = 0.18; //0.13;
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
public static double spindexer_intakePos3 = 0.56; //0.53;//0.66;
public static double spindexer_intakePos3 = 0.55; //0.53;//0.66;
public static double spindexer_outtakeBall3 = 0.84; //0.65; //0.24;
public static double spindexer_outtakeBall3 = 0.83; //0.65; //0.24;
public static double spindexer_outtakeBall3b = 0.27; //0.65; //0.24;
public static double spindexer_outtakeBall2 = 0.66; //0.46; //0.6;
public static double spindexer_outtakeBall1 = 0.47; //0.27; //0.4;
public static double spinStartPos = 0.10;
public static double spinEndPos = 0.95;
public static double spindexer_outtakeBall2 = 0.65; //0.46; //0.6;
public static double spindexer_outtakeBall1 = 0.46; //0.27; //0.4;
public static double spinStartPos = 0;
public static double spinEndPos = 0.6;
public static double shootAllSpindexerSpeedIncrease = 0.014;
public static double shootAllSpindexerSpeedIncrease = 0.01;
public static double transferServo_out = 0.15;
public static double transferServo_out = 0.57;
public static double transferServo_in = 0.38;
public static double transferServo_in = 0.77;
public static double hoodAuto = 0.27;
public static double hoodOffset = -0.04; // offset from 0.93
public static double hoodOffset = 0; // offset from 0.93 (or position at 0,0 in targeting class)
public static double turret_redClose = 0;
public static double turret_blueClose = 0;
@@ -44,4 +57,10 @@ public class ServoPositions {
public static double redTurretShootPos = 0.05;
public static double blueTurretShootPos = -0.05;
public static double tilt1_down = 0.6;
public static double tilt2_down = 0.4;
public static double tilt1_up = 0.08;
public static double tilt2_up = 0.97;
}

View File

@@ -1,19 +0,0 @@
package org.firstinspires.ftc.teamcode.libs.pedroPathing;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.FollowerBuilder;
import com.pedropathing.paths.PathConstraints;
import com.qualcomm.robotcore.hardware.HardwareMap;
public class Constants {
public static FollowerConstants followerConstants = new FollowerConstants();
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1);
public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints)
.build();
}
}

View File

@@ -0,0 +1,60 @@
package org.firstinspires.ftc.teamcode.pedroPathing;
import com.acmerobotics.dashboard.config.Config;
import com.pedropathing.control.FilteredPIDFCoefficients;
import com.pedropathing.control.PIDFCoefficients;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.FollowerBuilder;
import com.pedropathing.ftc.drivetrains.MecanumConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.paths.PathConstraints;
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@Config
public class Constants {
public static FollowerConstants followerConstants = new FollowerConstants()
.mass(14.37888)
.forwardZeroPowerAcceleration(-30.322)
.lateralZeroPowerAcceleration(-60.876)
.translationalPIDFCoefficients(new PIDFCoefficients(0.15, 0, 0.015, 0.02))
.headingPIDFCoefficients(new PIDFCoefficients(1, 0, 0.02, 0.02))
.drivePIDFCoefficients(new FilteredPIDFCoefficients(0.02, 0, 0.00001, 0.6, 0.015))
.centripetalScaling(0.0005);
public static MecanumConstants driveConstants = new MecanumConstants()
.maxPower(1)
.rightFrontMotorName("fr")
.rightRearMotorName("br")
.leftRearMotorName("bl")
.leftFrontMotorName("fl")
.leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE)
.leftRearMotorDirection(DcMotorSimple.Direction.REVERSE)
.rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD)
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD)
.xVelocity(84.376)
.yVelocity(64.052);
public static double breakingStrength = 1;
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, breakingStrength, 1);
public static PinpointConstants localizerConstants = new PinpointConstants()
.forwardPodY(3.7795)
.strafePodX(-3.676)
.distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint")
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
.forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED)
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD);
public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints)
.mecanumDrivetrain(driveConstants)
.pinpointLocalizer(localizerConstants)
.build();
}
}

View File

@@ -1,7 +1,10 @@
package org.firstinspires.ftc.teamcode.teleop;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.shootAllSpindexerSpeedIncrease;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
@@ -9,15 +12,16 @@ 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.acmerobotics.roadrunner.Pose2d;
import com.arcrobotics.ftclib.controller.PIDFController;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.Pose;
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.StateEnums;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utils.Drivetrain;
import org.firstinspires.ftc.teamcode.utils.Flywheel;
import org.firstinspires.ftc.teamcode.utils.Light;
@@ -33,32 +37,35 @@ import java.util.List;
@Config
@TeleOp
public class TeleopV3 extends LinearOpMode {
private double metersToInches = 39.3700787402;
public static double manualVel = 3000;
public static double hoodDefaultPos = 0.5;
private double predictedResetX, predictedResetY, predictedResetH;
public static double redPredictedResetX = 9, redPredictedResetY = 10.25, redPredictedResetH = 0;
public static double bluePredictedResetX = 135.0, bluePredictedResetY = 9, bluePredictedResetH = 180;
public static double spinPow = 0.09;
public static double tp = 0.8, ti = 0.001, td = 0.0315, tf = 0;
public static double spinSpeedIncrease = 0.03;
public static int resetSpinTicks = 4;
public static int resetSpinTicks = 0;
public static double hoodSpeedOffset = 0.01;
public static double turretSpeedOffset = 0.01;
public double vel = 3000;
public boolean autoVel = true;
public boolean targetingHood = true;
// public boolean autoHood = true;
// public boolean autoHood = true;
public double shootStamp = 0.0;
// boolean fixedTurret = false;
// boolean fixedTurret = false;
Robot robot;
MultipleTelemetry TELE;
Light light;
Servos servo;
Flywheel flywheel;
MecanumDrive drive;
// MecanumDrive drive;
Spindexer spindexer;
Targeting targeting;
Targeting.Settings targetingSettings;
Drivetrain drivetrain;
MeasuringLoopTimes loopTimes;
Follower follower;
double autoHoodOffset = 0.0;
int shooterTicker = 0;
boolean intake = false;
@@ -66,22 +73,21 @@ public class TeleopV3 extends LinearOpMode {
double xOffset = 0.0;
double yOffset = 0.0;
double hOffset = 0.0;
// double headingOffset = 0.0;
// double headingOffset = 0.0;
int ticker = 0;
// boolean autoSpintake = false;
// boolean autoSpintake = false;
boolean enableSpindexerManager = true;
// boolean overrideTurr = false;
int intakeTicker = 0;
private boolean shootAll = false;
boolean relocalize = false;
public static boolean relocalize = false;
@Override
public void runOpMode() throws InterruptedException {
robot = new Robot(hardwareMap);
robot.light.setPosition(0);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) {
@@ -91,12 +97,15 @@ public class TeleopV3 extends LinearOpMode {
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
servo = new Servos(hardwareMap);
flywheel = new Flywheel(hardwareMap);
drive = new MecanumDrive(hardwareMap, teleStart);
// drive = new MecanumDrive(hardwareMap, teleStart);
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start);
spindexer = new Spindexer(hardwareMap);
targeting = new Targeting();
targetingSettings = new Targeting.Settings(0.0, 0.0);
drivetrain = new Drivetrain(robot, drive);
drivetrain = new Drivetrain(robot, follower);
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
@@ -112,23 +121,36 @@ public class TeleopV3 extends LinearOpMode {
light.setState(StateEnums.LightState.MANUAL);
limelightUsed = true;
Spindexer.teleop = true;
while (opModeInInit()) {
//ONLY FOR TESTING: COMMENT OUT FOR COMPETITIONS
if (gamepad1.crossWasPressed()){
redAlliance = !redAlliance;
}
robot.limelight.start();
if (redAlliance) {
turret.pipelineSwitch(4);
light.setManualLightColor(Color.LightRed);
predictedResetX = redPredictedResetX;
predictedResetY = redPredictedResetY;
predictedResetH = Math.toRadians(redPredictedResetH);
} else {
turret.pipelineSwitch(2);
light.setManualLightColor(Color.LightBlue);
predictedResetX = bluePredictedResetX;
predictedResetY = bluePredictedResetY;
predictedResetH = Math.toRadians(bluePredictedResetH);
}
robot.light.setPosition(1);
limelightUsed = true;
TELE.addData("Red Alliance?", redAlliance);
TELE.update();
light.update();
}
limelightUsed = true;
waitForStart();
if (isStopRequested()) return;
@@ -139,6 +161,62 @@ public class TeleopV3 extends LinearOpMode {
while (opModeIsActive()) {
//TELE.addData("Is limelight on?", robot.limelight.getStatus());
follower.update();
Pose currentPose = follower.getPose();
if (enableSpindexerManager) {
//if (!shootAll) {
spindexer.processIntake();
//}
// RIGHT_BUMPER
if (gamepad1.right_bumper && intakeTicker > resetSpinTicks) {
spindexer.setIntakePower(1);
} else if (gamepad1.cross) {
spindexer.setIntakePower(-1);
} else {
spindexer.setIntakePower(0);
}
// LEFT_BUMPER
if (!shootAll && gamepad1.leftBumperWasReleased()) {
shootStamp = getRuntime();
shootAll = true;
shooterTicker = 0;
}
intakeTicker++;
if (shootAll) {
intakeTicker = 0;
intake = false;
reject = false;
if (shooterTicker == 0) {
spindexer.prepareShootAllContinous();
//TELE.addLine("preparing to shoot");
// } else if (shooterTicker == 2) {
// //servo.setTransferPos(transferServo_in);
// spindexer.shootAll();
// TELE.addLine("starting to shoot");
} else if (spindexer.shootAllComplete()) {
//spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
//spindexer.processIntake();
//TELE.addLine("stop shooting");
}
shooterTicker++;
//spindexer.processIntake();
}
if (gamepad1.left_stick_button) {
// servo.setTransferPos(transferServo_out);
//spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
}
}
//DRIVETRAIN:
@@ -156,29 +234,31 @@ public class TeleopV3 extends LinearOpMode {
light.setState(StateEnums.LightState.BALL_COUNT);
} else if (gamepad2.triangle){
light.setState(StateEnums.LightState.BALL_COLOR);
//} else if (gamepad2.triangle){
//light.setState(StateEnums.LightState.BALL_COLOR);
//}
} else {
light.setState(StateEnums.LightState.GOAL_LOCK);
light.setState(StateEnums.LightState.BALL_COUNT);
}
//TURRET TRACKING
double robX = drive.localizer.getPose().position.x;
double robY = drive.localizer.getPose().position.y;
double robH = drive.localizer.getPose().heading.toDouble();
double robX = currentPose.getX();
double robY = currentPose.getY();
double robH = currentPose.getHeading();
double robotX = robX + xOffset;
double robotY = robY + yOffset;
double robotHeading = robH + hOffset;
double goalX = -15;
double goalY = 0;
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
// double goalX = -15;
// double goalY = 0;
//
// double dx = robotX - goalX; // delta x from robot to goal
// double dy = robotY - goalY; // delta y from robot to goal
// Pose deltaPose = new Pose(dx, dy, robotHeading);
Pose deltaPose = new Pose(robotX, robotY, robotHeading);
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
@@ -187,16 +267,19 @@ public class TeleopV3 extends LinearOpMode {
//RELOCALIZATION
if (gamepad2.squareWasPressed()){
if (gamepad2.triangleWasPressed()){
relocalize = !relocalize;
gamepad2.rumble(500);
}
if (relocalize){
turret.relocalize();
xOffset = -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset) - robX;
yOffset = (turret.getLimelightX() * 39.3701) - robY;
hOffset = (Math.toRadians(turret.getLimelightH())) - robH;
xOffset = ((turret.getLimelightY()*metersToInches)+72) - robX;
yOffset = (72-(turret.getLimelightX()*metersToInches)) - robY;
hOffset = (Math.toRadians(turret.getLimelightH() + 90));
while (hOffset > 180) {hOffset-=360;}
while (hOffset < -180) {hOffset+=360;}
hOffset = hOffset - robH;
} else {
turret.trackGoal(deltaPose);
}
@@ -263,67 +346,19 @@ public class TeleopV3 extends LinearOpMode {
}
if (gamepad2.crossWasPressed()) {
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
// drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
follower.setPose(new Pose(predictedResetX, predictedResetY, predictedResetH));
gamepad2.rumble(200);
sleep(500);
}
if (enableSpindexerManager) {
//if (!shootAll) {
spindexer.processIntake();
//}
// RIGHT_BUMPER
if (gamepad1.right_bumper && intakeTicker > resetSpinTicks) {
spindexer.setIntakePower(1);
} else if (gamepad1.cross) {
spindexer.setIntakePower(-1);
} else {
spindexer.setIntakePower(0);
}
// LEFT_BUMPER
if (!shootAll && gamepad1.leftBumperWasReleased()) {
shootStamp = getRuntime();
shootAll = true;
shooterTicker = 0;
}
intakeTicker++;
if (shootAll) {
intakeTicker = 0;
intake = false;
reject = false;
if (shooterTicker == 0) {
spindexer.prepareShootAllContinous();
//TELE.addLine("preparing to shoot");
// } else if (shooterTicker == 2) {
// //servo.setTransferPos(transferServo_in);
// spindexer.shootAll();
// TELE.addLine("starting to shoot");
} else if (spindexer.shootAllComplete()) {
//spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
//spindexer.processIntake();
//TELE.addLine("stop shooting");
}
shooterTicker++;
//spindexer.processIntake();
}
if (gamepad1.left_stick_button) {
servo.setTransferPos(transferServo_out);
//spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
}
if (gamepad2.squareWasPressed()){
shootAllSpindexerSpeedIncrease = shootAllSpindexerSpeedIncrease-0.01;
} else if (gamepad2.circleWasPressed()){
shootAllSpindexerSpeedIncrease = shootAllSpindexerSpeedIncrease+0.01;
}
//EXTRA STUFFINESS:
drive.updatePoseEstimate();
for (LynxModule hub : allHubs) {
hub.clearBulkCache();
@@ -369,9 +404,9 @@ public class TeleopV3 extends LinearOpMode {
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("Tag Pos X", -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset));
TELE.addData("Tag Pos Y", turret.getLimelightX() * 39.3701);
TELE.addData("Tag Pos H", Math.toRadians(turret.getLimelightH()));
// TELE.addData("Tag Pos X", -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset));
// TELE.addData("Tag Pos Y", turret.getLimelightX() * 39.3701);
// TELE.addData("Tag Pos H", Math.toRadians(turret.getLimelightH()));
TELE.update();

View File

@@ -0,0 +1,107 @@
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.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 TeleopV4 extends LinearOpMode {
Robot robot;
Drivetrain drivetrain;
Shooter shooter;
MultipleTelemetry TELE;
Follower follower;
SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
@Override
public void runOpMode() throws InterruptedException {
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(
FtcDashboard.getInstance().getTelemetry(), telemetry
);
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);
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel);
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE);
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x
);
shooter.update();
spindexerTransferIntake.update();
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
if (gamepad1.xWasPressed() &&
(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);
}
if (gamepad1.aWasPressed() &&
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
spindexerTransferIntake.setRapidMode(
SpindexerTransferIntake.RapidMode.HOLD_BALLS
);
}
if (gamepad1.yWasPressed()
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
spindexerTransferIntake.setRapidMode(
SpindexerTransferIntake.RapidMode.INTAKE
);
}
TELE.update();
}
}
}

View File

@@ -0,0 +1,141 @@
package org.firstinspires.ftc.teamcode.tests;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
@Config
@TeleOp
public class Hardware_Tester extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
public static boolean subsystemMode = true;
// Bare Motor Powers
public static double flPow = 0;
public static double frPow = 0;
public static double blPow = 0;
public static double brPow = 0;
public static double intakePow = 0;
public static double transferPow = 0;
public static double shooter1Pow = 0;
public static double shooter2Pow = 0;
// Subsystem Motor Powers
public static double drivetrainPow = 0;
public static double shooterPow = 0;
// Bare Servo Positions
public static double spin1Pos = 0.501;
public static double spin2Pos = 0.501;
public static double turr1Pos = 0.501;
public static double turr2Pos = 0.501;
public static double transferServosPos = 0.501;
public static double hoodPos = 0.501;
public static double spindexBlockerPos = 0.501;
public static double rapidFireBlockerPos = 0.501;
public static double tilt1Pos = 0.501;
public static double tilt2Pos = 0.501;
// Subsystem Servo Positions
public static double spinPos = 0.501;
public static double turrPos = 0.501;
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
robot.shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
// Non-subsystem based components
robot.setIntakePower(intakePow);
robot.setTransferPower(transferPow);
if (transferServosPos != 0.501){
robot.setTransferServoPos(transferServosPos);
}
if (hoodPos != 0.501){
robot.setHoodPos(hoodPos);
}
if (rapidFireBlockerPos != 0.501){
robot.setRapidFireBlockerPos(rapidFireBlockerPos);
}
if (spindexBlockerPos != 0.501){
robot.setSpindexBlockerPos(spindexBlockerPos);
}
if (tilt1Pos != 0.501){
robot.setTilt1Pos(tilt1Pos);
}
if (tilt2Pos != 0.501){
robot.setTilt2Pos(tilt2Pos);
}
// Subsystem based components
if (subsystemMode){
robot.setFrontLeftPower(drivetrainPow);
robot.setFrontRightPower(drivetrainPow);
robot.setBackLeftPower(drivetrainPow);
robot.setBackRightPower(drivetrainPow);
robot.shooter1.setPower(shooterPow);
robot.shooter2.setPower(shooterPow);
if (spinPos != 0.501){
robot.setSpinPos(spinPos);
}
if (turrPos != 0.501){
robot.setTurretPos(turrPos);
}
} else {
robot.setFrontLeftPower(flPow);
robot.setFrontRightPower(frPow);
robot.setBackLeftPower(blPow);
robot.setBackRightPower(brPow);
robot.shooter1.setPower(shooter1Pow);
robot.shooter2.setPower(shooter2Pow);
if (spin1Pos != 0.501){
robot.spin1.setPosition(spin1Pos);
}
if (spin2Pos != 0.501){
robot.spin2.setPosition(spin2Pos);
}
if (turr1Pos != 0.501){
robot.turr1.setPosition(turr1Pos);
}
if (turr2Pos != 0.501){
robot.turr2.setPosition(turr2Pos);
}
}
// Sensor Data
TELE.addData("Beam Break insideBeam?", robot.insideBeam.isPressed());
TELE.addData("Beam Break outsideBeam?", robot.outsideBeam.isPressed());
// TELE.addData("Beam Break 2?", robot.beam2.isPressed());
// TELE.addData("Beam Break 3?", robot.beam3.isPressed());
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.MM));
TELE.addData("REV Green", revColor.green / (revColor.red + revColor.blue + revColor.green));
TELE.addData("Voltage Sensor", robot.voltage.getVoltage());
TELE.update();
}
}
}

View File

@@ -0,0 +1,147 @@
package org.firstinspires.ftc.teamcode.tests;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import org.firstinspires.ftc.teamcode.utilsv2.Shooter;
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
@Config
@TeleOp
public class NewShooterTest extends LinearOpMode {
Robot robot;
Flywheel flywheel;
Turret turret;
MultipleTelemetry TELE;
public static boolean intake = true;
public static boolean shoot = false;
public static double intakePower = 1.0;
public static double transferShootPower = -1;
public static double transferIntakePower = -1;
public static double turretPos = 0.51;
public static double hoodPos = 0.51;
public static double flywheel_velo = 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
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
flywheel = new Flywheel(robot);
turret = new Turret(robot);
Shooter shooter = new Shooter(
robot,
TELE,
Constants.createFollower(hardwareMap),
true,
turret,
flywheel
);
shooter.setState(Shooter.ShooterState.MANUAL);
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
robot.setHoodPos(hoodPos);
shooter.setTurretPosition(turretPos);
shooter.setFlywheelVelocity(flywheel_velo);
double voltage = robot.voltage.getVoltage();
flywheel.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;
case WAIT_PUSH:
if (System.currentTimeMillis() - timestamp >= 100) {
robot.setTransferServoPos(
ServoPositions.transferServo_in);
shootState = ShootState.IDLE;
}
break;
}
}
TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28);
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28);
TELE.addData("Flywheel Averag Velocity", flywheel.getAverageVelocity());
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF);
TELE.addData("Power", flywheel.getShooterPower());
TELE.update();
shooter.update();
}
}
}

View File

@@ -8,13 +8,13 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinSpeedIncrease;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.roadrunner.Pose2d;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotorEx;
@@ -107,7 +107,7 @@ public class ShooterTest extends LinearOpMode {
double dx = robX - goalX; // delta x from robot to goal
double dy = robY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
Pose deltaPose = new Pose(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);

View File

@@ -65,46 +65,51 @@ public class SortingTest extends LinearOpMode {
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
spindexer.setIntakePower(1);
robot.transfer.setPower(1);
if (gamepad1.crossWasPressed()){
motif = 21;
} else if (gamepad1.squareWasPressed()){
motif = 22;
} else if (gamepad1.triangleWasPressed()){
motif = 23;
}
flywheel.manageFlywheel(2500);
if (gamepad1.leftBumperWasPressed()){
intaking = false;
if (opModeIsActive()){
Actions.runBlocking(
autoActions.prepareShootAll(
3,
5,
motif,
0.501,
0.501,
0.501
autoActions.ShakeDrivetrain(
100
)
);
} else if (gamepad1.rightBumperWasPressed()){
intaking = false;
Actions.runBlocking(
autoActions.shootAllAuto(
3.5,
0.014,
0.501,
0.501,
0.501
)
);
intaking = true;
} else if (intaking){
spindexer.processIntake();
}
// spindexer.setIntakePower(1);
// robot.transfer.setPower(1);
//
// if (gamepad1.crossWasPressed()){
// motif = 21;
// } else if (gamepad1.squareWasPressed()){
// motif = 22;
// } else if (gamepad1.triangleWasPressed()){
// motif = 23;
// }
// flywheel.manageFlywheel(2500);
//
// if (gamepad1.leftBumperWasPressed()){
// intaking = false;
// Actions.runBlocking(
// autoActions.prepareShootAll(
// 3,
// 5,
// motif,
// 0.501,
// 0.501,
// 0.501
// )
// );
// } else if (gamepad1.rightBumperWasPressed()){
// intaking = false;
// Actions.runBlocking(
// autoActions.shootAllAuto(
// 3.5,
// 0.014,
// 0.501,
// 0.501,
// 0.501
// )
// );
// intaking = true;
// } else if (intaking){
// spindexer.processIntake();
// }
}
}
}

View File

@@ -4,11 +4,14 @@ import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.roadrunner.Pose2d;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.Pose;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Turret;
@@ -25,26 +28,31 @@ public class TurretTest extends LinearOpMode {
);
Turret turret = new Turret(robot, TELE, robot.limelight);
Follower follower;
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(72, 72, 0);
follower.setStartingPose(start);
follower.update();
waitForStart();
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
Turret.limelightUsed = false;
while(opModeIsActive()){
follower.update();
turret.trackGoal(follower.getPose());
drive.updatePoseEstimate();
turret.trackGoal(drive.localizer.getPose());
// TELE.addData("tpos", turret.getTurrPos());
// TELE.addData("Limelight tx", turret.getBearing());
// TELE.addData("Limelight ty", turret.getTy());
// TELE.addData("Limelight X", turret.getLimelightX());
// TELE.addData("Limelight Y", turret.getLimelightY());
TELE.addData("tpos", turret.getTurrPos());
TELE.addData("Limelight tx", turret.getBearing());
TELE.addData("Limelight ty", turret.getTy());
TELE.addData("Limelight X", turret.getLimelightX());
TELE.addData("Limelight Y", turret.getLimelightY());
// if(zeroTurr){
// turret.zeroTurretEncoder();
// }
if(zeroTurr){
turret.zeroTurretEncoder();
}
TELE.update();
// TELE.update();
}
}

View File

@@ -1,54 +1,76 @@
package org.firstinspires.ftc.teamcode.utils;
import com.acmerobotics.roadrunner.Pose2d;
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.PathChain;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Gamepad;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
public class Drivetrain {
Robot robot;
boolean autoDrive = false;
Pose2d brakePos = new Pose2d(0, 0, 0);
Pose brakePos = new Pose(0, 0, 0);
MecanumDrive drive;
// MecanumDrive drive;
Follower follower;
private final TranslationalVelConstraint VEL_CONSTRAINT = new TranslationalVelConstraint(200);
private final ProfileAccelConstraint ACCEL_CONSTRAINT = new ProfileAccelConstraint(-Math.abs(60), 200);
public Drivetrain (Robot rob, MecanumDrive mecanumDrive){
public Drivetrain(Robot rob, Follower follower){
this.robot = rob;
this.drive = mecanumDrive;
this.follower = follower;
}
private double prevY = 0;
private double prevX = 0;
private double prevRX = 0;
private double prevBrake = 0;
public void drive(double y, double x, double rx, double brake){
int countConstant = 0;
boolean brakeChange = false;
if (Math.abs(prevY - y) > 0.05){
prevY = y;
countConstant++;
}
if (Math.abs(prevX - x) > 0.05){
prevX = x;
countConstant++;
}
if (Math.abs(prevRX - rx) > 0.05){
prevRX = rx;
countConstant++;
}
if (Math.abs(prevBrake - brake) > 0.05){
prevBrake = brake;
brakeChange = true;
}
if (!autoDrive) {
if (!autoDrive && countConstant > 0) {
x = x* 1.1; // Counteract imperfect strafing
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
double frontLeftPower = (y + x + rx) / denominator;
double backLeftPower = (y - x + rx) / denominator;
double frontRightPower = (y - x - rx) / denominator;
double backRightPower = (y + x - rx) / denominator;
double denominator = Math.max(Math.abs(prevY) + Math.abs(prevX) + Math.abs(prevRX), 1);
double frontLeftPower = (prevY + prevX + prevRX) / denominator;
double backLeftPower = (prevY - prevX + prevRX) / denominator;
double frontRightPower = (prevY - prevX - prevRX) / denominator;
double backRightPower = (prevY + prevX - prevRX) / denominator;
robot.frontLeft.setPower(frontLeftPower);
robot.backLeft.setPower(backLeftPower);
robot.frontRight.setPower(frontRightPower);
robot.backRight.setPower(backRightPower);
}
Pose currentPos = follower.getPose();
brakePos = currentPos;
if (brake > 0.4 && robot.frontLeft.getZeroPowerBehavior() != DcMotor.ZeroPowerBehavior.BRAKE && !autoDrive) {
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
@@ -56,23 +78,17 @@ public class Drivetrain {
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
drive.updatePoseEstimate();
brakePos = drive.localizer.getPose();
autoDrive = true;
} else if (brake > 0.4) {
drive.updatePoseEstimate();
Pose2d currentPos = drive.localizer.getPose();
PathChain traj2 = follower.pathBuilder()
.addPath(new BezierLine(currentPos, brakePos))
.setLinearHeadingInterpolation(currentPos.getHeading(), brakePos.getHeading())
.build();
TrajectoryActionBuilder traj2 = drive.actionBuilder(currentPos)
.strafeToLinearHeading(new Vector2d(brakePos.position.x, brakePos.position.y), brakePos.heading.toDouble(), VEL_CONSTRAINT, ACCEL_CONSTRAINT);
if (Math.abs(currentPos.position.x - brakePos.position.x) > 1 || Math.abs(currentPos.position.y - brakePos.position.y) > 1) {
Actions.runBlocking(
traj2.build()
);
if (Math.abs(currentPos.getX() - brakePos.getX()) > 1 || Math.abs(currentPos.getY() - brakePos.getY()) > 1) {
follower.followPath(traj2);
}
} else {
autoDrive = false;

View File

@@ -64,17 +64,17 @@ public final class Light {
break;
case BALL_COLOR:
if ((System.currentTimeMillis() % ballColorCycleTime) < ((ballColorCycleTime / 3) - restingTime)) {
double currentTime = System.currentTimeMillis();
if ((currentTime % ballColorCycleTime) < ((ballColorCycleTime / 3) - restingTime)) {
lightColor = spindexer.getRearCenterLight();
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime / 3)) {
} else if ((currentTime % ballColorCycleTime) < (ballColorCycleTime / 3)) {
lightColor = 0;
} else if ((System.currentTimeMillis() % ballColorCycleTime) < ((2 * ballColorCycleTime / 3) - restingTime)) {
} else if ((currentTime % ballColorCycleTime) < ((2 * ballColorCycleTime / 3) - restingTime)) {
lightColor = spindexer.getDriverLight();
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (2 * ballColorCycleTime / 3)) {
} else if ((currentTime % ballColorCycleTime) < (2 * ballColorCycleTime / 3)) {
lightColor = 0;
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime - restingTime)) {
} else if ((currentTime % ballColorCycleTime) < (ballColorCycleTime - restingTime)) {
lightColor = spindexer.getPassengerLight();
} else {

View File

@@ -43,7 +43,7 @@ public class MeasuringLoopTimes {
public void loop() {
currentTime = getTimeSeconds();
if ((MeasurementStart + 15.0) < currentTime)
if ((MeasurementStart + 5.0) < currentTime)
{
minLoopTime = 9999999.0;
maxLoopTime = 0.0;

View File

@@ -10,6 +10,7 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.TouchSensor;
import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
@@ -38,12 +39,22 @@ public class Robot {
public DcMotorEx shooter2;
public Servo hood;
public Servo transferServo;
public Servo spindexBlocker;
public Servo rapidFireBlocker;
public Servo tilt1;
public Servo tilt2;
public Servo turr1;
public Servo turr2;
public Servo spin1;
public Servo spin2;
public TouchSensor beam1;
public TouchSensor beam2;
public TouchSensor beam3;
public RevColorSensorV3 revSensor;
public VoltageSensor voltage;
// Below is disregarded
public AnalogInput spin1Pos;
public AnalogInput spin2Pos;
public AnalogInput turr1Pos;
@@ -55,7 +66,6 @@ public class Robot {
public RevColorSensorV3 color3;
public Limelight3A limelight;
public Servo light;
public VoltageSensor voltage;
public Robot(HardwareMap hardwareMap) {
@@ -73,6 +83,7 @@ public class Robot {
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
intake = hardwareMap.get(DcMotorEx.class, "intake");
intake.setDirection(DcMotorSimple.Direction.REVERSE);
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
@@ -89,34 +100,50 @@ public class Robot {
hood = hardwareMap.get(Servo.class, "hood");
turr1 = hardwareMap.get(Servo.class, "t1");
turr1 = hardwareMap.get(Servo.class, "turr1");
turr2 = hardwareMap.get(Servo.class, "t2");
turr2 = hardwareMap.get(Servo.class, "turr2");
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
spin1 = hardwareMap.get(Servo.class, "spin1");
spin1 = hardwareMap.get(Servo.class, "spin2");
spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
spin2 = hardwareMap.get(Servo.class, "spin1");
spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
spin2 = hardwareMap.get(Servo.class, "spin2");
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
transferServo = hardwareMap.get(Servo.class, "transferServo");
transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
spindexBlocker = hardwareMap.get(Servo.class, "spinB");
color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
rapidFireBlocker = hardwareMap.get(Servo.class, "rapidB");
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
tilt1 = hardwareMap.get(Servo.class, "tilt1");
tilt2 = hardwareMap.get(Servo.class, "tilt2");
// beam1 = hardwareMap.get(TouchSensor.class, "beam1");
// beam2 = hardwareMap.get(TouchSensor.class, "beam2");
// beam3 = hardwareMap.get(TouchSensor.class, "beam3");
revSensor = hardwareMap.get(RevColorSensorV3.class, "rev");
// Below is disregarded
// turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
//
// spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
//
// spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
//
// transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
//
// color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
//
// color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
//
// color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
if (usingLimelight) {
limelight = hardwareMap.get(Limelight3A.class, "limelight");
@@ -125,7 +152,144 @@ public class Robot {
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
}
light = hardwareMap.get(Servo.class, "light");
// light = hardwareMap.get(Servo.class, "light");
voltage = hardwareMap.voltageSensor.iterator().next();
}
// Voids below are used to minimize hardware calls to minimize loop times
// Used to cut off digits that are negligible
private final int maxDigits = 5;
private final int roundingFactor = (int) Math.pow(10, maxDigits);
private double prevFrontLeftPower = -10.501;
public void setFrontLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevFrontLeftPower){
frontLeft.setPower(pow);
}
prevFrontLeftPower = pow;
}
private double prevFrontRightPower = -10.501;
public void setFrontRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevFrontRightPower){
frontRight.setPower(pow);
}
prevFrontRightPower = pow;
}
private double prevBackLeftPower = -10.501;
public void setBackLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevBackLeftPower){
backLeft.setPower(pow);
}
prevBackLeftPower = pow;
}
private double prevBackRightPower = -10.501;
public void setBackRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevBackRightPower){
backRight.setPower(pow);
}
prevBackRightPower = pow;
}
private double prevIntakePower = -10.501;
public void setIntakePower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevIntakePower){
intake.setPower(pow);
}
prevIntakePower = pow;
}
private double prevTransferPower = -10.501;
public void setTransferPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevTransferPower){
transfer.setPower(pow);
}
prevTransferPower = pow;
}
// shooter motors are done in separate class
private double prevHoodPos = -10.501;
public void setHoodPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevHoodPos){
hood.setPosition(pos);
}
prevHoodPos = pos;
}
private double prevTransferServoPos = -10.501;
public void setTransferServoPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTransferServoPos){
transferServo.setPosition(pos);
}
prevTransferServoPos = pos;
}
private double prevSpinPos = -10.501;
public void setSpinPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevSpinPos){
spin1.setPosition(pos);
spin2.setPosition(pos);
}
prevSpinPos = pos;
}
private double prevTurretPos = -10.501;
public void setTurretPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTurretPos){
turr1.setPosition(pos);
turr2.setPosition(pos);
}
prevTurretPos = pos;
}
private double prevTilt1Pos = -10.501;
public void setTilt1Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTilt1Pos){
tilt1.setPosition(pos);
}
prevTilt1Pos = pos;
}
private double prevTilt2Pos = -10.501;
public void setTilt2Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTilt2Pos){
tilt2.setPosition(pos);
}
prevTilt2Pos = pos;
}
private double prevSpindexBlockerPos = -10.501;
public void setSpindexBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevSpindexBlockerPos){
spindexBlocker.setPosition(pos);
}
prevSpindexBlockerPos = pos;
}
private double prevRapidFireBlockerPos = -10.501;
public void setRapidFireBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevRapidFireBlockerPos){
rapidFireBlocker.setPosition(pos);
}
prevRapidFireBlockerPos = pos;
}
}

View File

@@ -79,6 +79,6 @@ public class Servos {
}
public boolean spinEqual(double pos) {
return Math.abs(pos - this.getSpinPos()) < 0.03;
return Math.abs(pos - this.getSpinPos()) < 0.05;
}
}

View File

@@ -48,7 +48,7 @@ public class Spindexer {
public double distanceFrontDriver = 0.0;
public double distanceFrontPassenger = 0.0;
public double spindexerWiggle = 0.01;
public double spindexerWiggle = 0.03;
public double spindexerOuttakeWiggle = 0.01;
private double prevPos = 0.0;
@@ -173,10 +173,25 @@ public class Spindexer {
// Detects if a ball is found and what color.
// Returns true is there was a new ball found in Position 1
// FIXIT: Reduce number of times that we read the color sensors for loop times.
public static boolean teleop = false;
public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
boolean newPos1Detection = false;
int spindexerBallPos = 0;
double rearDistance;
double frontDriverDistance;
double frontPassengerDistance;
if (teleop){
rearDistance = 48;
frontDriverDistance = 50;
frontPassengerDistance = 29;
detectFrontColor = false;
detectRearColor = false;
} else {
rearDistance = 48;
frontDriverDistance = 56;
frontPassengerDistance = 29;
}
// Read Distances
double dRearCenter = robot.color1.getDistance(DistanceUnit.MM);
@@ -187,12 +202,12 @@ public class Spindexer {
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
// Position 1
if (distanceRearCenter < 48) {
if (distanceRearCenter < rearDistance) {
// Mark Ball Found
newPos1Detection = true;
if (detectRearColor) {
if (detectRearColor && !teleop) {
// Detect which color
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
@@ -209,10 +224,10 @@ public class Spindexer {
// Position 2
// Find which ball position this is in the spindexer
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
if (distanceFrontDriver < 50) {
if (distanceFrontDriver < frontDriverDistance) {
// reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0;
if (detectFrontColor) {
if (detectFrontColor && !teleop) {
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
double gP = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
@@ -235,11 +250,11 @@ public class Spindexer {
// Position 3
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
if (distanceFrontPassenger < 29) {
if (distanceFrontPassenger < frontPassengerDistance) {
// reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0;
if (detectFrontColor) {
if (detectFrontColor && !teleop) {
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
double gP = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
@@ -367,6 +382,7 @@ public class Spindexer {
commandedIntakePosition = 0;
servos.setSpinPos(intakePositions[0]);
currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
servos.setTransferPos(transferServo_out);
break;
case UNKNOWN_MOVE:
// Stopping when we get to the new position
@@ -378,6 +394,7 @@ public class Spindexer {
// Keep moving the spindexer
servos.setSpinPos(intakePositions[commandedIntakePosition]);
}
servos.setTransferPos(transferServo_out);
break;
case UNKNOWN_DETECT:
if (unknownColorDetect >5) {
@@ -386,6 +403,7 @@ public class Spindexer {
//detectBalls(true, true);
unknownColorDetect++;
}
servos.setTransferPos(transferServo_out);
break;
case INTAKE:
// Ready for intake and Detecting a New Ball
@@ -397,6 +415,7 @@ public class Spindexer {
spindexerWiggle *= -1.0;
servos.setSpinPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
}
servos.setTransferPos(transferServo_out);
break;
case FINDNEXT:
// Find Next Open Position and start movement
@@ -428,23 +447,24 @@ public class Spindexer {
currentIntakeState = Spindexer.IntakeState.FULL;
}
servos.setSpinPos(intakePositions[commandedIntakePosition]);
servos.setTransferPos(transferServo_out);
break;
case MOVING:
// Stopping when we get to the new position
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
if (intakeTicker > 1){
//if (intakeTicker > 1){
currentIntakeState = Spindexer.IntakeState.INTAKE;
stopSpindexer();
intakeTicker = 0;
} else {
intakeTicker++;
}
//} else {
// intakeTicker++;
//}
//detectBalls(false, false);
} else {
// Keep moving the spindexer
servos.setSpinPos(intakePositions[commandedIntakePosition]);
}
servos.setTransferPos(transferServo_out);
break;
case FULL:
@@ -457,6 +477,7 @@ public class Spindexer {
// Maintain Position
spindexerWiggle *= -1.0;
servos.setSpinPos(intakePositions[commandedIntakePosition]+spindexerWiggle);
servos.setTransferPos(transferServo_out);
break;
case SHOOT_ALL_PREP:
@@ -535,13 +556,11 @@ public class Spindexer {
break;
case SHOOT_PREP_CONTINOUS:
if (shootTicks > waitFirstBallTicks){
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
shootTicks++;
} else if (servos.spinEqual(spinStartPos)){
shootTicks++;
if (servos.spinEqual(spinStartPos)){
servos.setTransferPos(transferServo_in);
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
} else {
servos.setTransferPos(transferServo_out);
servos.setSpinPos(spinStartPos);
}
break;
@@ -557,7 +576,7 @@ public class Spindexer {
shootTicks = 0;
currentIntakeState = IntakeState.FINDNEXT;
} else {
double spinPos = servos.getSpinCmdPos() + shootAllSpindexerSpeedIncrease;
double spinPos = robot.spin1.getPosition() + shootAllSpindexerSpeedIncrease;
if (spinPos > spinEndPos + 0.03){
spinPos = spinEndPos + 0.03;
}
@@ -671,10 +690,8 @@ public class Spindexer {
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
}
private double prevPow = 0.501;
private boolean firstIntakePow = true;
public void setIntakePower(double pow){
if (firstIntakePow || prevPow != pow){
firstIntakePow = false;
if (prevPow != 0.501 && prevPow != pow){
robot.intake.setPower(pow);
}
prevPow = pow;

View File

@@ -1,9 +1,12 @@
package org.firstinspires.ftc.teamcode.utils;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import java.lang.Math;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
public class Targeting {
@@ -71,7 +74,7 @@ public class Targeting {
public final int TILE_UPPER_QUARTILE = 18;
public final int TILE_LOWER_QUARTILE = 6;
public double robotInchesX, robotInchesY = 0.0;
public int robotGridX, robotGridY = 0;
public int robotGridX = 0, robotGridY = 0;
MultipleTelemetry TELE;
double cancelOffsetX = 0.0; // was -40.0
double cancelOffsetY = 0.0; // was 7.0
@@ -82,40 +85,64 @@ public class Targeting {
public Targeting() {
}
double cos54 = Math.cos(Math.toRadians(-54));
double sin54 = Math.sin(Math.toRadians(-54));
//TODO: change code so it uses pedropathing paths
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
Settings recommendedSettings = new Settings(0.0, 0.0);
if (!redAlliance){
sin54 = Math.sin(Math.toRadians(54));
} else {
sin54 = Math.sin(Math.toRadians(-54));
}
// TODO: test these values determined from the fmap
double rotatedY = (robotX + cancelOffsetX) * sin54 + (robotY + cancelOffsetY) * cos54;
double rotatedX = (robotX + cancelOffsetX) * cos54 - (robotY + cancelOffsetY) * sin54;
// Convert robot coordinates to inches
robotInchesX = rotatedX * unitConversionFactor;
robotInchesY = rotatedY * unitConversionFactor;
// Find approximate location in the grid
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
int remX = Math.floorMod((int) robotInchesX, tileSize);
int remY = Math.floorMod((int) robotInchesY, tileSize);
//clamp
//if (redAlliance) {
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
//} else {
int gridX;
int gridY;
int remX = 0;
int remY = 0;
// Old code
// if (!redAlliance){
// sin54 = Math.sin(Math.toRadians(54));
// double rotatedY = (robotX + cancelOffsetX) * sin54 + (robotY + cancelOffsetY) * cos54;
// double rotatedX = (robotX + cancelOffsetX) * cos54 - (robotY + cancelOffsetY) * sin54;
//
// // Convert robot coordinates to inches
// robotInchesX = rotatedX * unitConversionFactor + 20;
// robotInchesY = rotatedY * unitConversionFactor + 20;
//
// // Find approximate location in the grid
// gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize));
// gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
// } else {
// sin54 = Math.sin(Math.toRadians(-54));
// double rotatedY = (robotX + cancelOffsetX) * sin54 + (robotY + cancelOffsetY) * cos54;
// double rotatedX = (robotX + cancelOffsetX) * cos54 - (robotY + cancelOffsetY) * sin54;
//
// // Convert robot coordinates to inches
// robotInchesX = rotatedX * unitConversionFactor;
// robotInchesY = rotatedY * unitConversionFactor;
//
// // Find approximate location in the grid
// gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
// gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
// }
//
//
remX = Math.floorMod((int) robotX, tileSize);
remY = Math.floorMod((int) robotY, tileSize);
//
// //clamp
//
// if (redAlliance) {
// robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
// robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
//}
// } else {
// robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
// robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
// }
// New code
if (redAlliance){
gridY = Math.round((float) (((144-robotX)-12) / 24));
} else {
gridY = Math.round((float) ((robotX-12) / 24));
}
gridX = Math.round((float) (((144-robotY)-12) / 24));
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
// Determine if we need to interpolate based on tile position.
// if near upper or lower quarter or tile interpolate with next tile.
@@ -192,7 +219,7 @@ public class Targeting {
if (true) { //!interpolate) {
if ((robotGridY < 6) && (robotGridX < 6)) {
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle + hoodOffset;
}
return recommendedSettings;
} else {

View File

@@ -6,6 +6,7 @@ import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.roadrunner.Pose2d;
import com.arcrobotics.ftclib.controller.PIDController;
import com.pedropathing.geometry.Pose;
import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.hardware.limelightvision.Limelight3A;
@@ -13,6 +14,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.teleop.TeleopV3;
import java.util.ArrayList;
import java.util.List;
@@ -23,10 +25,10 @@ public class Turret {
public static double turretTolerance = 0.02;
public static double turrPosScalar = 0.00011264432;
public static double turret180Range = 0.54;
public static double turrDefault = 0.35;
public static double turrMin = 0;
public static double turrMax = 1;
public static double turret180Range = 0.58;
public static double turrDefault = 0.51;
public static double turrMin = 0.05;
public static double turrMax = 0.95;
public static boolean limelightUsed = true;
public static double limelightPosOffset = 5;
public static double manualOffset = 0.0;
@@ -79,7 +81,7 @@ public class Turret {
}
public double getTurrPos() {
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
return robot.turr1.getPosition();
}
private double prevTurrPos = 0;
@@ -107,41 +109,27 @@ public class Turret {
private void limelightRead() { // only for tracking purposes, not general reads
Double xPos = null;
Double yPos = null;
Double zPos = null;
double zPos;
Double hPos = null;
result = webcam.getLatestResult();
if (result != null) {
if (result.isValid()) {
tx = result.getTx();
ty = result.getTy();
// MegaTag1 code for receiving position
Pose3D botpose = result.getBotpose();
if (botpose != null) {
limelightPosX = botpose.getPosition().x;
limelightPosY = botpose.getPosition().y;
}
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
for (LLResultTypes.FiducialResult fiducial : fiducials) {
limelightTagPose = fiducial.getRobotPoseTargetSpace();
if (limelightTagPose != null){
xPos = limelightTagPose.getPosition().x;
yPos = limelightTagPose.getPosition().y;
zPos = limelightTagPose.getPosition().z;
hPos = limelightTagPose.getOrientation().getYaw();
}
}
}
}
if (xPos != null){
if (zPos<0) {
if (TeleopV3.relocalize){
zPos = result.getBotpose().getPosition().z;
if (zPos < 0.15){
xPos = result.getBotpose().getPosition().x;
yPos = result.getBotpose().getPosition().y;
hPos = result.getBotpose().getOrientation().getYaw();
limelightTagX = (alphaPosConstant * xPos) + ((1 - alphaPosConstant) * limelightTagX);
limelightTagY = (alphaPosConstant * yPos) + ((1 - alphaPosConstant) * limelightTagY);
limelightTagZ = (alphaPosConstant * zPos) + ((1 - alphaPosConstant) * limelightTagZ);
limelightTagH = (alphaPosConstant * hPos) + ((1 - alphaPosConstant) * limelightTagH);
}
}
}
}
}
public double getBearing() {
tx = 1000;
@@ -153,7 +141,6 @@ public class Turret {
return ty;
}
Pose3D limelightTagPose;
double limelightTagX = 0.0;
double limelightTagY = 0.0;
double limelightTagZ = 0.0;
@@ -246,17 +233,31 @@ public class Turret {
return bearingOffset;
}
public void trackGoal(Pose2d deltaPos) {
double targetTurretPos;
public void trackGoal(Pose deltaPos) {
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
double posX;
if (Color.redAlliance){
posX = 134 - deltaPos.getX();
} else {
posX = deltaPos.getX() - 10;
}
double posY = 140 - deltaPos.getY();
double posH = Math.toDegrees(deltaPos.getHeading());
while (posH > 180) posH -= 360;
while (posH < -180) posH += 360;
// Angle from robot to goal in robot frame
double desiredTurretAngleDeg = Math.toDegrees(
Math.atan2(deltaPos.position.y, deltaPos.position.x)
);
double desiredTurretAngleDeg = Math.toDegrees(Math.atan2(posY, posX)) - 45;
// Robot heading (field → robot)
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
double robotHeadingDeg;
if (Color.redAlliance){
robotHeadingDeg = posH + 135;
} else {
robotHeadingDeg = posH + 45;
}
// Turret angle needed relative to robot
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
@@ -277,7 +278,7 @@ public class Turret {
limelightRead();
// Active correction if we see the target
if (result.isValid() && !lockOffset && limelightUsed) {
if (result.isValid() && !lockOffset && limelightUsed && targetTurretPos > turrMin && targetTurretPos < turrMax) {
currentTrackOffset += bearingAlign(result);
currentTrackCount++;
@@ -333,7 +334,7 @@ public class Turret {
/* ---------------- ANGLE → SERVO POSITION ---------------- */
double targetTurretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
targetTurretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
// Clamp to physical servo limits
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
@@ -358,13 +359,14 @@ public class Turret {
// TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
// TELE.addData("Target Pos", "%.3f", targetTurretPos);
// TELE.addData("Current Pos", "%.3f", currentPos);
// TELE.addData("Current Localization Pos", deltaPos);
// TELE.addData("Commanded Pos", "%.3f", turretPos);
// TELE.addData("LL Valid", result.isValid());
// TELE.addData("LL getTx", result.getTx());
// TELE.addData("LL Offset", offset);
// TELE.addData("Bearing Error", hasValidTarget ? String.format("%.2f", tagBearingDeg) : "NO TARGET");
// TELE.addData("Learned Offset", "%.2f", offset);
// TELE.update();
}
}

View File

@@ -0,0 +1,96 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.hardware.DcMotor;
@Config
public class Drivetrain {
Robot robot;
MultipleTelemetry telemetry;
private static final double DEADZONE = 0.15;
private static final double AXIS_SNAP_THRESHOLD = 0.12;
private static final double STRAFE_MULTIPLIER = 1.2;
public static double FORWARD_ROTATION_CORRECTION = 0;
public static double STRAFE_ROTATION_CORRECTION = -0;
private boolean tele = false;
public Drivetrain(Robot rob, MultipleTelemetry TELE) {
this.robot = rob;
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
this.telemetry = TELE;
}
public void setTelemetry(boolean input) {
tele = input;
}
public void drive(double y, double x, double rx) {
boolean snappedForward = false;
boolean snappedStrafe = false;
if (Math.abs(y) < DEADZONE) y = 0;
if (Math.abs(x) < DEADZONE) x = 0;
if (Math.abs(rx) < DEADZONE) rx = 0;
if (Math.abs(x) < AXIS_SNAP_THRESHOLD) {
x = 0;
snappedForward = true;
}
if (Math.abs(y) < AXIS_SNAP_THRESHOLD) {
y = 0;
snappedStrafe = true;
}
x *= STRAFE_MULTIPLIER;
double correctionRX = 0;
if (rx == 0) {
correctionRX += (y * FORWARD_ROTATION_CORRECTION);
correctionRX += (x * STRAFE_ROTATION_CORRECTION);
rx += correctionRX;
}
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
double frontLeftPower = (y + x + rx) / denominator;
double backLeftPower = (y - x + rx) / denominator;
double frontRightPower = (y - x - rx) / denominator;
double backRightPower = (y + x - rx) / denominator;
robot.setFrontLeftPower(frontLeftPower);
robot.setBackLeftPower(backLeftPower);
robot.setFrontRightPower(frontRightPower);
robot.setBackRightPower(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

@@ -0,0 +1,132 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import java.util.LinkedList;
public class Flywheel {
Robot robot;
// public PIDFCoefficients shooterPIDF1, shooterPIDF2;
public static PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
private double velo = 0.0;
private double velo1 = 0.0;
private double velo2 = 0.0;
private double averageVelocity = 0.0;
double targetVelocity = 0.0;
boolean steady = false;
private final LinkedList<Double> velocityHistory = new LinkedList<>();
public Flywheel(Robot rob) {
robot = rob;
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
}
public double getVelo() {
return velo;
}
public double getVelo1() {
return velo1;
}
public double getVelo2() {
return velo2;
}
public double getAverageVelocity() {
return averageVelocity;
}
public boolean getSteady() {
return steady;
}
// Set the robot PIDF for the next cycle.
public void setPIDF(double p, double i, double d, double f) {
shooterPIDF.p = p;
shooterPIDF.i = i;
shooterPIDF.d = d;
shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
}
private double prevF = 0;
public static double voltagePIDFDifference = 0.8;
public void setF(double f){
if (Math.abs(prevF - f) > voltagePIDFDifference) {
shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f;
}
}
// Convert from RPM to Ticks per Second
private double RPM_to_TPS(double RPM) {
return (RPM * 28.0) / 60.0;
}
// Convert from Ticks per Second to RPM
private double TPS_to_RPM(double TPS) {
return (TPS * 60.0) / 28.0;
}
private void updateVelocityAverage(double 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();
}
double power;
public void manageFlywheel(double commandedVelocity) {
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
targetVelocity = commandedVelocity;
}
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
power = robot.shooter1.getPower();
robot.shooter2.setPower(power);
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = (velo1 + velo2) / 2.0;
updateVelocityAverage(velo);
steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
}
public double getShooterPower(){return power;}
}

View File

@@ -0,0 +1,305 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import android.view.View;
import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.hardware.rev.RevColorSensorV3;
import com.qualcomm.robotcore.hardware.AnalogInput;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.TouchSensor;
import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
public class Robot {
// Singleton instance
private static Robot instance;
/**
* Returns the existing Robot instance or creates one if it doesn't exist.
*/
public static Robot getInstance(HardwareMap hardwareMap) {
if (instance == null) {
instance = new Robot(hardwareMap);
}
return instance;
}
/**
* Optional: clears the singleton.
* Useful when switching OpModes.
*/
public static void resetInstance() {
instance = null;
}
public static boolean usingLimelight = true;
public static boolean usingCamera = false;
public DcMotorEx frontLeft;
public DcMotorEx frontRight;
public DcMotorEx backLeft;
public DcMotorEx backRight;
public DcMotorEx intake;
public DcMotorEx transfer;
// public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public DcMotorEx shooter1;
public DcMotorEx shooter2;
public Servo hood;
public Servo transferServo;
public Servo spindexBlocker;
public Servo rapidFireBlocker;
public Servo tilt1;
public Servo tilt2;
public Servo turr1;
public Servo turr2;
public Servo spin1;
public Servo spin2;
public TouchSensor insideBeam;
public TouchSensor outsideBeam;
public RevColorSensorV3 revSensor;
public VoltageSensor voltage;
// Below is disregarded
public AnalogInput spin1Pos;
public AnalogInput spin2Pos;
public AnalogInput turr1Pos;
public AnalogInput transferServoPos;
public AprilTagProcessor aprilTagProcessor;
public WebcamName webcam;
public RevColorSensorV3 color1;
public RevColorSensorV3 color2;
public RevColorSensorV3 color3;
public Limelight3A limelight;
public Servo light;
public Robot(HardwareMap hardwareMap) {
//Define components w/ hardware map
frontLeft = hardwareMap.get(DcMotorEx.class, "fl");
frontRight = hardwareMap.get(DcMotorEx.class, "fr");
backLeft = hardwareMap.get(DcMotorEx.class, "bl");
backRight = hardwareMap.get(DcMotorEx.class, "br");
frontLeft.setDirection(DcMotorSimple.Direction.REVERSE);
backLeft.setDirection(DcMotorSimple.Direction.REVERSE);
frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);
intake = hardwareMap.get(DcMotorEx.class, "intake");
intake.setDirection(DcMotorSimple.Direction.REVERSE);
shooter1 = hardwareMap.get(DcMotorEx.class, "shooter1");
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
// shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
// shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
hood = hardwareMap.get(Servo.class, "hood");
turr1 = hardwareMap.get(Servo.class, "turr1");
turr2 = hardwareMap.get(Servo.class, "turr2");
spin1 = hardwareMap.get(Servo.class, "spin1");
spin2 = hardwareMap.get(Servo.class, "spin2");
transfer = hardwareMap.get(DcMotorEx.class, "transfer");
transferServo = hardwareMap.get(Servo.class, "transferServo");
transfer.setDirection(DcMotorSimple.Direction.REVERSE);
transfer.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
spindexBlocker = hardwareMap.get(Servo.class, "spinB");
rapidFireBlocker = hardwareMap.get(Servo.class, "rapidB");
tilt1 = hardwareMap.get(Servo.class, "tilt1");
tilt2 = hardwareMap.get(Servo.class, "tilt2");
insideBeam = hardwareMap.get(TouchSensor.class, "beam1");
outsideBeam = hardwareMap.get(TouchSensor.class, "beam2");
revSensor = hardwareMap.get(RevColorSensorV3.class, "rev");
// Below is disregarded
// turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
//
// spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos");
//
// spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos");
//
// transferServoPos = hardwareMap.get(AnalogInput.class, "tSPos");
//
// color1 = hardwareMap.get(RevColorSensorV3.class, "c1");
//
// color2 = hardwareMap.get(RevColorSensorV3.class, "c2");
//
// color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
if (usingLimelight) {
limelight = hardwareMap.get(Limelight3A.class, "limelight");
} else if (usingCamera) {
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
}
// light = hardwareMap.get(Servo.class, "light");
voltage = hardwareMap.voltageSensor.iterator().next();
}
// Voids below are used to minimize hardware calls to minimize loop times
// Used to cut off digits that are negligible
private final int maxDigits = 5;
private final int roundingFactor = (int) Math.pow(10, maxDigits);
private double prevFrontLeftPower = -10.501;
public void setFrontLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevFrontLeftPower){
frontLeft.setPower(pow);
}
prevFrontLeftPower = pow;
}
private double prevFrontRightPower = -10.501;
public void setFrontRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevFrontRightPower){
frontRight.setPower(pow);
}
prevFrontRightPower = pow;
}
private double prevBackLeftPower = -10.501;
public void setBackLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevBackLeftPower){
backLeft.setPower(pow);
}
prevBackLeftPower = pow;
}
private double prevBackRightPower = -10.501;
public void setBackRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevBackRightPower){
backRight.setPower(pow);
}
prevBackRightPower = pow;
}
private double prevIntakePower = -10.501;
public void setIntakePower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevIntakePower){
intake.setPower(pow);
}
prevIntakePower = pow;
}
private double prevTransferPower = -10.501;
public void setTransferPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
if (pow != prevTransferPower){
transfer.setPower(pow);
}
prevTransferPower = pow;
}
// shooter motors are done in separate class
private double prevHoodPos = -10.501;
public void setHoodPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevHoodPos){
hood.setPosition(pos);
}
prevHoodPos = pos;
}
private double prevTransferServoPos = -10.501;
public void setTransferServoPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTransferServoPos){
transferServo.setPosition(pos);
}
prevTransferServoPos = pos;
}
private double prevSpinPos = -10.501;
public void setSpinPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevSpinPos){
spin1.setPosition(pos);
spin2.setPosition(pos);
}
prevSpinPos = pos;
}
private double prevTurretPos = -10.501;
public void setTurretPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTurretPos){
turr1.setPosition(pos);
turr2.setPosition(pos);
}
prevTurretPos = pos;
}
private double prevTilt1Pos = -10.501;
public void setTilt1Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTilt1Pos){
tilt1.setPosition(pos);
}
prevTilt1Pos = pos;
}
private double prevTilt2Pos = -10.501;
public void setTilt2Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevTilt2Pos){
tilt2.setPosition(pos);
}
prevTilt2Pos = pos;
}
private double prevSpindexBlockerPos = -10.501;
public void setSpindexBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevSpindexBlockerPos){
spindexBlocker.setPosition(pos);
}
prevSpindexBlockerPos = pos;
}
private double prevRapidFireBlockerPos = -10.501;
public void setRapidFireBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
if (pos != prevRapidFireBlockerPos){
rapidFireBlocker.setPosition(pos);
}
prevRapidFireBlockerPos = pos;
}
}

View File

@@ -0,0 +1,161 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
public class Shooter {
Robot robot;
Flywheel fly;
Turret turr;
VelocityCommander commander;
double goalX = 0.0;
double goalY = 0.0;
double obeliskX = 72;
double obeliskY = 144;
private boolean red = true;
Follower follow;
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel) {
this.robot = rob;
this.fly = flywheel;
this.turr = turret;
this.follow = follower;
this.commander = new VelocityCommander();
setRedAlliance(redAlliance);
}
public void setRedAlliance(boolean input) {
this.red = input;
if (this.red) {
goalX = 144;
} else {
goalX = 0;
}
goalY = 144;
}
private double flywheelVelocity = 0.0;
private double turretPosition = 0.5;
public enum ShooterState {
READ_OBELISK,
TRACK_GOAL,
MANUAL_FLYWHEEL_TRACK_TURR,
MANUAL_TURRET_TRACK_FLY,
MANUAL,
NOTHING
}
private ShooterState state = ShooterState.NOTHING;
public void setState(ShooterState shooterState) {
this.state = shooterState;
}
public void setTurretPosition(double input) {
this.turretPosition = input;
}
public void setFlywheelVelocity(double input) {
this.flywheelVelocity = input;
}
public int getObeliskID() {
return turr.getObeliskID();
}
public void update() {
switch (state) {
case NOTHING:
break;
case MANUAL:
fly.manageFlywheel(flywheelVelocity);
turr.manual(turretPosition);
break;
case TRACK_GOAL:
turr.trackGoal(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getHeading(),
follow.getAngularVelocity(),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent()
);
flywheelVelocity = commander.getVeloPredictive(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent()
);
fly.manageFlywheel(flywheelVelocity);
break;
case READ_OBELISK:
turr.trackObelisk(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getHeading()
);
flywheelVelocity = commander.getVeloPredictive(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent()
);
fly.manageFlywheel(flywheelVelocity);
break;
case MANUAL_TURRET_TRACK_FLY:
turr.manual(turretPosition);
flywheelVelocity = commander.getVeloPredictive(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent()
);
fly.manageFlywheel(flywheelVelocity);
break;
case MANUAL_FLYWHEEL_TRACK_TURR:
turr.trackGoal(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getHeading(),
follow.getAngularVelocity(),
follow.getVelocity().getXComponent(),
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent()
);
fly.manageFlywheel(flywheelVelocity);
break;
}
}
}

View File

@@ -0,0 +1,183 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
public class SpindexerTransferIntake {
private final Robot robot;
public SpindexerTransferIntake(Robot rob, MultipleTelemetry TELE) {
this.robot = rob;
}
private final double sensorDistanceThreshold = 4.0;
private final long pulseTime = 50; // ms
public enum SpindexerMode {
RAPID,
SORTED
}
public enum RapidMode {
INTAKE,
TRANSFER_OFF,
BEFORE_PULSE_OUT,
PULSE_OUT,
PULSE_IN,
HOLD_BALLS,
OPEN_GATE,
SHOOT
}
private SpindexerMode mode = SpindexerMode.RAPID;
private RapidMode rapidMode = RapidMode.INTAKE;
/**
* Time when current state was entered.
*/
private long stateStartTime = System.currentTimeMillis();
public void setRapidMode(RapidMode newMode) {
if (rapidMode != newMode) {
rapidMode = newMode;
stateStartTime = System.currentTimeMillis();
}
}
public void setSpindexerMode(SpindexerMode spindexerMode) {
this.mode = spindexerMode;
}
public RapidMode getRapidState(){
return this.rapidMode;
}
private long stateTime() {
return System.currentTimeMillis() - stateStartTime;
}
public void update() {
switch (mode) {
case RAPID:
robot.setSpindexBlockerPos(
ServoPositions.spindexBlocker_Open
);
switch (rapidMode) {
case INTAKE:
robot.setIntakePower(1);
robot.setTransferPower(1);
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Closed
);
robot.setSpinPos(
ServoPositions.spindexer_A2
);
robot.setTransferServoPos(
ServoPositions.transferServo_out
);
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
setRapidMode(RapidMode.TRANSFER_OFF);
}
break;
case TRANSFER_OFF:
robot.setTransferPower(0.3);
if (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed()) {
setRapidMode(RapidMode.BEFORE_PULSE_OUT);
}
break;
case BEFORE_PULSE_OUT:
robot.setIntakePower(1.0);
if (stateTime() >= 300) {
setRapidMode(RapidMode.PULSE_OUT);
}
break;
case PULSE_OUT:
robot.setIntakePower(-0.1);
if (stateTime() >= pulseTime) {
setRapidMode(RapidMode.PULSE_IN);
}
break;
case PULSE_IN:
robot.setIntakePower(1.0);
if (stateTime() >= 200) {
setRapidMode(RapidMode.HOLD_BALLS);
}
break;
case HOLD_BALLS:
if (robot.insideBeam.isPressed()
&& robot.outsideBeam.isPressed()) {
robot.setIntakePower(0.1);
} else {
robot.setIntakePower(1);
}
break;
case OPEN_GATE:
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open
);
if (stateTime() >= 100) {
setRapidMode(RapidMode.SHOOT);
}
break;
case SHOOT:
robot.setTransferServoPos(
ServoPositions.transferServo_in
);
if (stateTime() >= 400) {
setRapidMode(RapidMode.INTAKE);
}
break;
}
break;
case SORTED:
// Future sorted-intake logic
break;
}
}
}

View File

@@ -0,0 +1,111 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.util.Range;
import java.util.List;
@Config
public class Turret {
Robot robot;
private final double servoTicksPer180 = 0.58;
private final double neutralPosition = 0.51;
private final double turretMin = 0.05;
private final double turretMax = 0.95;
private final double hVelK = 0; // TODO: Tune
private final double xVelK = 0; // TODO: Tune
private final double xAccK = 0; // TODO: Tune
private final double yVelK = 0; // TODO: Tune
private final double yAccK = 0; // TODO: Tune
private int obeliskID = 0;
public Turret(Robot rob) {
this.robot = rob;
}
private double wrapAngle(double angle) {
while (angle > Math.PI) angle -= 2.0 * Math.PI;
while (angle < -Math.PI) angle += 2.0 * Math.PI;
return angle;
}
public void trackObelisk(double dx, double dy, double h) {
double heading = wrapAngle(h);
double fieldRelativeHeading = Math.atan2(dy, dx);
double desiredAngle = fieldRelativeHeading - heading;
double angleDelta = desiredAngle - Math.PI;
angleDelta = wrapAngle(angleDelta);
double servoTicksFromNeutral = (angleDelta / (2.0 * Math.PI)) * (2.0 * servoTicksPer180);
double servoAngle = neutralPosition + servoTicksFromNeutral;
servoAngle = Range.clip(servoAngle, turretMin, turretMax);
robot.setTurretPos(servoAngle);
detectObelisk();
}
public int getObeliskID() {
return obeliskID;
}
private int detectObelisk() {
robot.limelight.pipelineSwitch(1);
LLResult result = robot.limelight.getLatestResult();
if (result != null && result.isValid()) {
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
double prevTx = -1000;
for (LLResultTypes.FiducialResult fiducial : fiducials) {
double currentTx = fiducial.getTargetXDegrees();
if (currentTx > prevTx){
obeliskID = fiducial.getFiducialId();
}
}
}
return obeliskID;
}
public void manual (double pos) {
robot.setTurretPos(pos);
}
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
// h is the raw heading where 0 degrees is positive x in the system of x, y
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 predictedH = h + (hVel * hVelK); // Positive bc h = robot heading
predictedH = wrapAngle(predictedH);
double fieldRelativeHeading = Math.atan2(predictedDy, predictedDx);
double angleDelta = fieldRelativeHeading - predictedH;
angleDelta = wrapAngle(angleDelta);
double servoTicksFromNeutral = (angleDelta / (2.0 * Math.PI)) * (2.0 * servoTicksPer180);
double servoAngle = neutralPosition + servoTicksFromNeutral;
servoAngle = Range.clip(servoAngle, turretMin, turretMax);
robot.setTurretPos(servoAngle);
}
}

View File

@@ -0,0 +1,34 @@
package org.firstinspires.ftc.teamcode.utilsv2;
public class VelocityCommander {
private final double goalH = 20.0; //TODO: Tune
private final double xVelK = 0; // TODO: Tune
private final double xAccK = 0; // TODO: Tune
private final double yVelK = 0; // TODO: Tune
private final double yAccK = 0; // TODO: Tune
public VelocityCommander() {
}
private double distToRPM (double dist){
return Math.sqrt(dist*dist + goalH*goalH);
//TODO: Add regression here using goalH
}
public double getVeloStationary (double distance){
return distToRPM(distance);
}
public double getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc) {
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 predictedDist = Math.sqrt(dx*dx + dy*dy);
return distToRPM(predictedDist);
}
}

View File

@@ -6,7 +6,6 @@ repositories {
maven { url = 'https://maven.brott.dev/' } //RR
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
maven { url = "https://repo.dairy.foundation/releases" } //AS
}
dependencies {
@@ -22,11 +21,9 @@ dependencies {
implementation 'androidx.appcompat:appcompat:1.2.0'
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
implementation 'com.pedropathing:ftc:2.1.1'
implementation 'com.pedropathing:telemetry:1.0.0'
implementation 'com.bylazar:fullpanels:1.0.12'
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC