Compare commits
125 Commits
f6b402dbf5
...
add-sorted
| Author | SHA1 | Date | |
|---|---|---|---|
| 9b92a59a75 | |||
| cca86f3691 | |||
| 8c2a655c5c | |||
| 9a4aca90ba | |||
| a3479d8816 | |||
| e9b9ffc3b8 | |||
| e7056812b4 | |||
| c15b9d58d4 | |||
| deefa19be4 | |||
| 3ae976c16d | |||
| 05f59d1820 | |||
| 128826f4fd | |||
| a89535830b | |||
| 209c34b3fd | |||
| d8cf594828 | |||
| e658ec044c | |||
| 12e5fba938 | |||
| 47c505742a | |||
| c8e9be1c08 | |||
| 28451ce26d | |||
| 9c3b4c2010 | |||
| 7665957c7a | |||
| ccc6a608fc | |||
| 8eba32de94 | |||
| 5c9ebf6eac | |||
| a540d333f1 | |||
| 180e7629bf | |||
| ae25df0393 | |||
| 946deca751 | |||
| 75b9b7b6b1 | |||
| 1a1c99791d | |||
| 88cf03a230 | |||
| 82c8ebf941 | |||
| aabc746a2e | |||
| f14dc3681a | |||
| 184ec893a4 | |||
| f32f31a224 | |||
| bfb37f13f8 | |||
| ccc0e2123a | |||
| a470b7dbc4 | |||
| dd2890ea4a | |||
| 76f58308fb | |||
| 658e8ea1d0 | |||
| 9ab69f8fbe | |||
| ed970eaf38 | |||
| e3105a339d | |||
| 6e31da5f1c | |||
| 4567a4117c | |||
| 9502576876 | |||
| a7bce4f6db | |||
| fb0df810e8 | |||
| 2a012ea3ae | |||
| 99216c1e80 | |||
| 3f2d54065f | |||
| 222b201561 | |||
| 81e0e80f62 | |||
| 7eebd42ea2 | |||
| 2a29e8181b | |||
| 6b092bdaeb | |||
| 4cbb09e088 | |||
| a8d28928e2 | |||
| f3efc132e7 | |||
| 6c905f2506 | |||
| 1723f6f85d | |||
| 6a3f65d4c5 | |||
| e40695b4f6 | |||
| 8f66ddc4bd | |||
| 08ba099d5b | |||
| 7043274ebd | |||
| bd05090afe | |||
| 369e379eb4 | |||
| 41853e9ad1 | |||
| 9ba5aebc8b | |||
| 128637e8a1 | |||
| 37dca729f0 | |||
| fb9cbb1c71 | |||
| b342c98149 | |||
| 6743481440 | |||
| 76dc6b12bf | |||
| a1340c5388 | |||
| e8d28b9e5f | |||
| f9013f4d79 | |||
| c42fce2e78 | |||
| c01edd9308 | |||
| ccfac3e123 | |||
| 395d4439db | |||
| 5f33cb4d41 | |||
| e92f11bc69 | |||
| 457eaf5feb | |||
| dc9886855b | |||
| 194100e3c8 | |||
| 64b2fed8d6 | |||
| 2ccd7f04f8 | |||
| 1ae4e1c3ed | |||
| 7a2b275e66 | |||
| 0264cf2c77 | |||
| f69bffc3ee | |||
| 09347ce479 | |||
| 102693d94a | |||
| c2e0b69c55 | |||
| 82c16b5402 | |||
| 5a456e211f | |||
| e87c5bb845 | |||
| a695f19cc6 | |||
| 1ad33fd45b | |||
| 56b61ee88b | |||
| 1ee40b472a | |||
| 3268d5cd02 | |||
| 44caad767b | |||
| dd1db74059 | |||
| 7161933d06 | |||
| 0f556a193f | |||
| 85989d54b9 | |||
| 2b9b0a140b | |||
| 18d9857b7a | |||
| 1c3100966c | |||
| 78c65c9d93 | |||
| 28816a6e34 | |||
| d0c34132de | |||
| 04ea56e31d | |||
| b616a41a08 | |||
| d18fedf8eb | |||
| 7d8dee7c3c | |||
| da944661a4 | |||
| a4755bf668 |
@@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -1,648 +0,0 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous.actions;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Drivetrain;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
import java.util.Objects;
|
||||
|
||||
public class Actions{
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Servos servos;
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
Spindexer spindexer;
|
||||
Targeting targeting;
|
||||
Targeting.Settings targetingSettings;
|
||||
Turret turret;
|
||||
private int driverSlotGreen = 0;
|
||||
private int passengerSlotGreen = 0;
|
||||
private int rearSlotGreen = 0;
|
||||
private int mostGreenSlot = 0;
|
||||
private double firstSpindexShootPos = spinStartPos;
|
||||
private boolean shootForward = true;
|
||||
public static double firstShootTime = 0.3;
|
||||
public int motif = 0;
|
||||
|
||||
public Actions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur){
|
||||
this.robot = rob;
|
||||
this.drive = dri;
|
||||
this.TELE = tel;
|
||||
this.servos = ser;
|
||||
this.flywheel = fly;
|
||||
this.spindexer = spi;
|
||||
this.targeting = tar;
|
||||
this.targetingSettings = tS;
|
||||
this.turret = tur;
|
||||
}
|
||||
public Action prepareShootAll(double colorSenseTime, double time, int motif_id) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
double spindexerWiggle = 0.01;
|
||||
|
||||
boolean decideGreenSlot = false;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
servos.setTransferPos(transferServo_out);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
double robX = drive.localizer.getPose().position.x;
|
||||
double robY = drive.localizer.getPose().position.y;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robX - goalX; // delta x from robot to goal
|
||||
double dy = robY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.addData("motif", motif_id);
|
||||
TELE.update();
|
||||
|
||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
||||
|
||||
spindexerWiggle *= -1.0;
|
||||
|
||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
||||
|
||||
spindexer.detectBalls(true, true);
|
||||
|
||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
||||
driverSlotGreen++;
|
||||
}
|
||||
|
||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
||||
passengerSlotGreen++;
|
||||
}
|
||||
|
||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
||||
rearSlotGreen++;
|
||||
}
|
||||
|
||||
spindexer.setIntakePower(1);
|
||||
|
||||
decideGreenSlot = true;
|
||||
|
||||
return true;
|
||||
} else if (decideGreenSlot) {
|
||||
|
||||
if (driverSlotGreen >= passengerSlotGreen && driverSlotGreen >= rearSlotGreen) {
|
||||
mostGreenSlot = 3;
|
||||
} else if (passengerSlotGreen >= driverSlotGreen && passengerSlotGreen >= rearSlotGreen) {
|
||||
mostGreenSlot = 2;
|
||||
} else {
|
||||
mostGreenSlot = 1;
|
||||
}
|
||||
|
||||
decideGreenSlot = false;
|
||||
|
||||
if (motif_id == 21) {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
}
|
||||
} else if (motif_id == 22) {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return true;
|
||||
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
||||
// TELE.addData("MostGreenSlot", mostGreenSlot);
|
||||
// TELE.update();
|
||||
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
||||
|
||||
servos.setSpinPos(firstSpindexShootPos);
|
||||
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAll(int vel, double shootTime, double spindexSpeed) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
double stamp = 0.0;
|
||||
double velo = vel;
|
||||
int shooterTicker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(vel);
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
spindexer.setIntakePower(-0.3);
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
spindexer.setIntakePower(0);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
double robX = drive.localizer.getPose().position.x;
|
||||
double robY = drive.localizer.getPose().position.y;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robX - goalX; // delta x from robot to goal
|
||||
double dy = robY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
if ((System.currentTimeMillis() - stamp < shootTime && servos.getSpinPos() < spinEndPos) || shooterTicker == 0) {
|
||||
|
||||
if (shooterTicker == 0 && !servos.spinEqual(spinStartPos)) {
|
||||
servos.setSpinPos(spinStartPos);
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_in);
|
||||
shooterTicker++;
|
||||
double prevSpinPos = servos.getSpinCmdPos();
|
||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
return false;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAllAuto(double shootTime, double spindexSpeed) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
|
||||
double stamp = 0.0;
|
||||
|
||||
double velo = 0.0;
|
||||
|
||||
int shooterTicker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
velo = flywheel.getVelo();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
spindexer.setIntakePower(-0.3);
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
spindexer.setIntakePower(0);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
double robX = drive.localizer.getPose().position.x;
|
||||
double robY = drive.localizer.getPose().position.y;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robX - goalX; // delta x from robot to goal
|
||||
double dy = robY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robX, robY, robotHeading, 0.0, turretInterpolate);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
if (System.currentTimeMillis() - stamp < shootTime) {
|
||||
|
||||
if (System.currentTimeMillis() - stamp < firstShootTime) {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
servos.setSpinPos(firstSpindexShootPos);
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_in);
|
||||
shooterTicker++;
|
||||
double prevSpinPos = servos.getSpinCmdPos();
|
||||
|
||||
if (shootForward) {
|
||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||
} else {
|
||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
return false;
|
||||
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(double intakeTime) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
ticker++;
|
||||
|
||||
spindexer.processIntake();
|
||||
spindexer.setIntakePower(1);
|
||||
|
||||
spindexer.ballCounterLight();
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
TELE.addData("Full?", spindexer.isFull());
|
||||
TELE.update();
|
||||
|
||||
return ((System.currentTimeMillis() - stamp) < (intakeTime * 1000)) && !spindexer.isFull();
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action detectObelisk(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance,
|
||||
double turrPos
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
robot.limelight.pipelineSwitch(1);
|
||||
}
|
||||
|
||||
ticker++;
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
turret.setTurret(turrPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
if (shouldFinish){
|
||||
if (redAlliance){
|
||||
robot.limelight.pipelineSwitch(4);
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
}
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageFlywheel(
|
||||
double vel,
|
||||
double hoodPos,
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(vel);
|
||||
servos.setHoodPos(hoodPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
return !shouldFinish;
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageShooterAuto(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
double robotX = drive.localizer.getPose().position.x;
|
||||
double robotY = drive.localizer.getPose().position.y;
|
||||
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX, robotY, robotHeading, 0.0, false);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
return !shouldFinish;
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageFlywheelAuto(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
double robotX = drive.localizer.getPose().position.x;
|
||||
double robotY = drive.localizer.getPose().position.y;
|
||||
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX, robotY, robotHeading, 0.0, false);
|
||||
|
||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || xDone || yDone;
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Hood", robot.hood.getPosition());
|
||||
TELE.update();
|
||||
|
||||
return !shouldFinish;
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,719 @@
|
||||
package org.firstinspires.ftc.teamcode.autonomous.actions;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.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;
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
import java.util.Objects;
|
||||
|
||||
@Config
|
||||
public class AutoActions {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Servos servos;
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
Spindexer spindexer;
|
||||
Targeting targeting;
|
||||
Targeting.Settings targetingSettings;
|
||||
Light light;
|
||||
Turret turret;
|
||||
private int driverSlotGreen = 0;
|
||||
private int passengerSlotGreen = 0;
|
||||
private int rearSlotGreen = 0;
|
||||
private int mostGreenSlot = 0;
|
||||
public static double firstSpindexShootPos = spinStartPos;
|
||||
private boolean shootForward = true;
|
||||
public int motif = 0;
|
||||
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;
|
||||
this.TELE = tel;
|
||||
this.servos = ser;
|
||||
this.flywheel = fly;
|
||||
this.spindexer = spi;
|
||||
this.targeting = tar;
|
||||
this.targetingSettings = tS;
|
||||
this.turret = tur;
|
||||
this.light = lig;
|
||||
}
|
||||
|
||||
public Action prepareShootAll(
|
||||
double colorSenseTime,
|
||||
double time,
|
||||
int motif_id,
|
||||
double posX,
|
||||
double posY,
|
||||
double posH
|
||||
) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
double spindexerWiggle = 0.01;
|
||||
|
||||
boolean decideGreenSlot = false;
|
||||
|
||||
void spin1PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
|
||||
void spin2PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
}
|
||||
|
||||
void reverseSpin2PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
|
||||
void spin3PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
}
|
||||
|
||||
void oddSpin3PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
|
||||
Action manageShooter = null;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||
driverSlotGreen = 0;
|
||||
passengerSlotGreen = 0;
|
||||
rearSlotGreen = 0;
|
||||
}
|
||||
ticker++;
|
||||
servos.setTransferPos(transferServo_out);
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
light.setState(StateEnums.LightState.GOAL_LOCK);
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
TELE.addData("Most Green Slot", mostGreenSlot);
|
||||
TELE.addData("Driver Slot Greeness", driverSlotGreen);
|
||||
TELE.addData("Passenger Slot Greeness", passengerSlotGreen);
|
||||
TELE.addData("Rear Greeness", rearSlotGreen);
|
||||
TELE.update();
|
||||
|
||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
||||
|
||||
spindexerWiggle *= -1.0;
|
||||
|
||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
||||
|
||||
|
||||
// Rear Center (Position 1)
|
||||
double distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||
if (distanceRearCenter < 52) {
|
||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||
if (gP1 >= 0.38) {
|
||||
rearSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
// Front Driver (Position 2)
|
||||
double distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||
if (distanceFrontDriver < 50) {
|
||||
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
|
||||
double gP2 = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
|
||||
if (gP2 >= 0.4) {
|
||||
driverSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
// Front Passenger (Position 3)
|
||||
double distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||
if (distanceFrontPassenger < 29) {
|
||||
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
|
||||
double gP3 = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
|
||||
if (gP3 >= 0.4) {
|
||||
passengerSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
spindexer.setIntakePower(-0.1);
|
||||
|
||||
decideGreenSlot = true;
|
||||
|
||||
return true;
|
||||
} else if (decideGreenSlot) {
|
||||
|
||||
if (driverSlotGreen >= passengerSlotGreen && driverSlotGreen >= rearSlotGreen) {
|
||||
mostGreenSlot = 3;
|
||||
} else if (passengerSlotGreen >= driverSlotGreen && passengerSlotGreen >= rearSlotGreen) {
|
||||
mostGreenSlot = 2;
|
||||
} else {
|
||||
mostGreenSlot = 1;
|
||||
}
|
||||
|
||||
decideGreenSlot = false;
|
||||
|
||||
if (motif_id == 21) {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
} else if (motif_id == 22) {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.03;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (mostGreenSlot == 1) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95; }
|
||||
}
|
||||
|
||||
return true;
|
||||
} else if ((System.currentTimeMillis() - stamp) < (time * 1000)) {
|
||||
spindexer.setIntakePower(-((System.currentTimeMillis() - stamp - colorSenseTime)) / 1000);
|
||||
|
||||
servos.setSpinPos(firstSpindexShootPos);
|
||||
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAllAuto(double shootTime, double spindexSpeed, double posX, double posY, double posH) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
|
||||
double stamp = 0.0;
|
||||
|
||||
int shooterTicker = 0;
|
||||
Action manageShooter = null;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
spindexer.setIntakePower(-0.1);
|
||||
|
||||
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||
light.update();
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterAuto(shootTime, posX, posY, posH, false);
|
||||
|
||||
}
|
||||
ticker++;
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
double prevSpinPos = servos.getSpinCmdPos();
|
||||
|
||||
boolean end;
|
||||
if (shootForward) {
|
||||
end = servos.getSpinPos() > spinEndPos;
|
||||
} else {
|
||||
end = servos.getSpinPos() < spinEndPos;
|
||||
}
|
||||
|
||||
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
|
||||
|
||||
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 1) {
|
||||
servos.setSpinPos(firstSpindexShootPos);
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_in);
|
||||
shooterTicker++;
|
||||
Spindexer.whileShooting = true;
|
||||
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
Spindexer.whileShooting = false;
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
return false;
|
||||
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAllManual(
|
||||
double shootTime,
|
||||
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||
double spindexSpeed,
|
||||
double velStart,
|
||||
double hoodStart,
|
||||
double velEnd,
|
||||
double hoodEnd,
|
||||
double turr) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
|
||||
double stamp = 0.0;
|
||||
|
||||
int shooterTicker = 0;
|
||||
Action manageShooter = null;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
spindexer.setIntakePower(-0.1);
|
||||
|
||||
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||
light.update();
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterManual(shootTime, hoodMoveTime, velStart, hoodStart, velEnd, hoodEnd, turr);
|
||||
|
||||
}
|
||||
ticker++;
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
double prevSpinPos = servos.getSpinCmdPos();
|
||||
|
||||
boolean end;
|
||||
if (shootForward) {
|
||||
end = prevSpinPos > spinEndPos;
|
||||
} else {
|
||||
end = prevSpinPos < spinEndPos;
|
||||
}
|
||||
|
||||
if (System.currentTimeMillis() - stamp < shootTime * 1000 && !end) {
|
||||
servos.setTransferPos(transferServo_in);
|
||||
shooterTicker++;
|
||||
Spindexer.whileShooting = true;
|
||||
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
Spindexer.whileShooting = false;
|
||||
spindexer.resetSpindexer();
|
||||
spindexer.processIntake();
|
||||
|
||||
return false;
|
||||
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action intake(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posH
|
||||
) {
|
||||
return new Action() {
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
Action manageShooter = null;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||
}
|
||||
ticker++;
|
||||
|
||||
spindexer.processIntake();
|
||||
spindexer.setIntakePower(1);
|
||||
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||
light.update();
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
|
||||
servos.setSpinPos(spindexer_intakePos1);
|
||||
intaking = false;
|
||||
return false;
|
||||
} else {
|
||||
intaking = true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
private boolean detectingObelisk = false;
|
||||
|
||||
public Action detectObelisk(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posXTolerance,
|
||||
double posYTolerance,
|
||||
double turrPos
|
||||
) {
|
||||
|
||||
boolean timeFallback = (time != 0.501);
|
||||
boolean posXFallback = (posX != 0.501);
|
||||
boolean posYFallback = (posY != 0.501);
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
int prevMotif = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
detectingObelisk = true;
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
turret.pipelineSwitch(1);
|
||||
ticker++;
|
||||
}
|
||||
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
if (prevMotif == motif){
|
||||
ticker++;
|
||||
}
|
||||
prevMotif = motif;
|
||||
|
||||
turret.setTurret(turrPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull() || ticker > 10;
|
||||
|
||||
teleStart = currentPose;
|
||||
|
||||
if (shouldFinish) {
|
||||
if (redAlliance) {
|
||||
turret.pipelineSwitch(4);
|
||||
} else {
|
||||
turret.pipelineSwitch(2);
|
||||
}
|
||||
detectingObelisk = false;
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageShooterAuto(
|
||||
double time,
|
||||
double posX,
|
||||
double posY,
|
||||
double posH,
|
||||
boolean flywheelSensor
|
||||
) {
|
||||
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
final boolean timeFallback = (time != 0.501);
|
||||
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = null; //drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
|
||||
if (redAlliance) {
|
||||
turret.pipelineSwitch(4);
|
||||
light.setManualLightColor(Color.LightRed);
|
||||
} else {
|
||||
turret.pipelineSwitch(2);
|
||||
light.setManualLightColor(Color.LightBlue);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
double robotX = 0.0;//currentPose.position.x;
|
||||
double robotY = 0.0;//currentPose.position.y;
|
||||
|
||||
double robotHeading = 0.0;//currentPose.heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
|
||||
|
||||
Pose deltaPose;
|
||||
if (posX != 0.501) {
|
||||
deltaPose = new Pose(posX, posY, Math.toRadians(posH));
|
||||
} else {
|
||||
deltaPose = new Pose(dx, dy, robotHeading);
|
||||
}
|
||||
Turret.limelightUsed = true;
|
||||
|
||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX, robotY, robotHeading, 0.0, false);
|
||||
|
||||
if (!detectingObelisk) {
|
||||
turret.trackGoal(deltaPose);
|
||||
}
|
||||
|
||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean shouldFinish = timeDone || (flywheel.getSteady() && flywheelSensor);
|
||||
|
||||
teleStart = currentPose;
|
||||
|
||||
TELE.addData("Steady?", flywheel.getSteady());
|
||||
TELE.update();
|
||||
|
||||
return !shouldFinish;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action Wait(double time) {
|
||||
return new Action() {
|
||||
boolean ticker = false;
|
||||
double stamp = 0.0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
if (!ticker) {
|
||||
stamp = System.currentTimeMillis();
|
||||
ticker = true;
|
||||
}
|
||||
|
||||
return (System.currentTimeMillis() - stamp < time * 1000);
|
||||
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
public Action manageShooterManual(
|
||||
double maxTime,
|
||||
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||
double velStart,
|
||||
double hoodStart,
|
||||
double velEnd,
|
||||
double hoodEnd,
|
||||
double turr
|
||||
) {
|
||||
return new Action() {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
final boolean timeFallback = (maxTime != 0.501);
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
ticker++;
|
||||
|
||||
double robotX = currentPose.position.x;
|
||||
double robotY = currentPose.position.y;
|
||||
|
||||
double robotHeading = currentPose.heading.toDouble();
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
Pose deltaPose;
|
||||
if (turr == 0.501) {
|
||||
deltaPose = new Pose(dx, dy, robotHeading);
|
||||
if (!detectingObelisk) {
|
||||
turret.trackGoal(deltaPose);
|
||||
}
|
||||
} else {
|
||||
turret.setTurret(turr);
|
||||
}
|
||||
|
||||
servos.setHoodPos(hoodStart + ((hoodEnd - hoodStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1)));
|
||||
double vel = velStart + (velEnd - velStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1);
|
||||
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(vel);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > maxTime * 1000;
|
||||
|
||||
teleStart = currentPose;
|
||||
|
||||
TELE.addData("Steady?", flywheel.getSteady());
|
||||
TELE.update();
|
||||
|
||||
return !timeDone;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -1,23 +1,35 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
|
||||
@Config
|
||||
public class Back_Poses {
|
||||
public static double rLeaveX = 90, rLeaveY = 80, rLeaveH = 50.1;
|
||||
public static double bLeaveX = 90, bLeaveY = -80, bLeaveH = -50;
|
||||
public static double rLeaveX = 90, rLeaveY = 50, rLeaveH = 50.1;
|
||||
public static double bLeaveX = 90, bLeaveY = -50, bLeaveH = -50;
|
||||
|
||||
public static double rShootX = 95, rShootY = 85, rShootH = 90;
|
||||
public static double bShootX = 95, bShootY = -85, 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 = 75, rStackPickupAY = 53, 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 = 50, rStackPickupBY = 78, rStackPickupBH = 140.1;
|
||||
public static double bStackPickupBX = 50, bStackPickupBY = -78, 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 Pose2d autoStart = new Pose2d(0, 0, 0); // TODO: find this position
|
||||
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 = 54;
|
||||
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -54;
|
||||
|
||||
}
|
||||
|
||||
@@ -7,40 +7,65 @@ 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 = 23, ry2b = 36, rh2b = 140.1;
|
||||
public static double bx2b = 19, by2b = -40, bh2b = -140.1;
|
||||
public static double rx2b = 21, ry2b = 34, rh2b = 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;
|
||||
|
||||
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
||||
public static double bx3aG = 55, by3aG = -43, bh3aG = -140;
|
||||
public static double bx3aG = 60, by3aG = -34, bh3aG = -140;
|
||||
|
||||
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
||||
public static double bx3b = 41, by3b = -59, bh3b = -140.1;
|
||||
public static double bx3b = 36, by3b = -58, bh3b = -140.1;
|
||||
|
||||
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
||||
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
||||
|
||||
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
||||
public static double bx4b = 47, by4b = -85, bh4b = -140.1;
|
||||
public static double bx4b = 50, by4b = -78, bh4b = -140.1;
|
||||
|
||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
||||
|
||||
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
||||
public static double bShootX = 40, bShootY = 0, bShootH = -50;
|
||||
public static double 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;
|
||||
|
||||
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 50;
|
||||
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -50;
|
||||
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 55;
|
||||
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -55;
|
||||
|
||||
public static double rShoot0X = 53, rShoot0Y = 10.1, rShoot0H = 80.1;
|
||||
public static double bShoot0X = 53, bShoot0Y = -10.1, bShoot0H = -80.1;
|
||||
|
||||
public static double rShootGateX = 50, rShootGateY = 10, rShootGateH = 90;
|
||||
public static double bShootGateX = 50, bShootGateY = -10, bShootGateH = -90;
|
||||
|
||||
public static double rLeaveGateX = 40, rLeaveGateY = -7, rLeaveGateH = 55;
|
||||
public static double bLeaveGateX = 40, bLeaveGateY = 7, bLeaveGateH = -55;
|
||||
|
||||
public static double rPickupGateAX = 31, rPickupGateAY = 53, rPickupGateAH = 150;
|
||||
public static double bPickupGateAX = 24, bPickupGateAY = -50, bPickupGateAH = -150;
|
||||
|
||||
public static double rPickupGateBX = 38, rPickupGateBY = 62, rPickupGateBH = 210;
|
||||
public static double bPickupGateBX = 38, bPickupGateBY = -68, bPickupGateBH = -180;
|
||||
public static double pickupGateCX = 34, pickupGateCY = 58, pickupGateCH = 220;
|
||||
|
||||
public static 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;
|
||||
}
|
||||
|
||||
@@ -5,41 +5,62 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
public class ServoPositions {
|
||||
|
||||
public static double spindexer_intakePos1 = 0.07; //0.13;
|
||||
public static double rapidFireBlocker_Closed = 0.35;
|
||||
public static double rapidFireBlocker_Open = 0.5;
|
||||
|
||||
public static double spindexer_intakePos2 = 0.27; //0.33;//0.5;
|
||||
public static double spindexBlocker_Closed = 0.31;
|
||||
public static double spindexBlocker_Open = 0.5;
|
||||
|
||||
public static double spindexer_intakePos3 = 0.46; //0.53;//0.66;
|
||||
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_outtakeBall3 = 0.71; //0.65; //0.24;
|
||||
public static double spindexer_outtakeBall3b = 0.15; //0.65; //0.24;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
||||
public static double spinStartPos = 0.22;
|
||||
public static double spinEndPos = 0.85;
|
||||
public static double spindexer_intakePos1 = 0.18; //0.13;
|
||||
|
||||
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
||||
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
|
||||
|
||||
public static double transferServo_out = 0.15;
|
||||
public static double spindexer_intakePos3 = 0.55; //0.53;//0.66;
|
||||
|
||||
public static double transferServo_in = 0.38;
|
||||
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.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.01;
|
||||
|
||||
public static double transferServo_out = 0.57;
|
||||
|
||||
public static double transferServo_in = 0.77;
|
||||
|
||||
public static double hoodAuto = 0.27;
|
||||
|
||||
public static double hoodOffset = -0.05;
|
||||
public static double hoodOffset = 0; // offset from 0.93 (or position at 0,0 in targeting class)
|
||||
|
||||
public static double turret_redClose = 0.42;
|
||||
public static double turret_blueClose = 0.38;
|
||||
public static double turret_redClose = 0;
|
||||
public static double turret_blueClose = 0;
|
||||
|
||||
// These values are ADDED to turrDefault
|
||||
public static double redObeliskTurrPos1 = 0.12;
|
||||
public static double redObeliskTurrPos2 = 0.13;
|
||||
public static double redObeliskTurrPos3 = 0.14;
|
||||
public static double blueObeliskTurrPos1 = -0.12;
|
||||
public static double blueObeliskTurrPos2 = -0.13;
|
||||
public static double blueObeliskTurrPos3 = -0.14;
|
||||
public static double redTurretShootPos = 0.1;
|
||||
public static double blueTurretShootPos = -0.14;
|
||||
public static double redObeliskTurrPos0 = -0.35;
|
||||
public static double redObeliskTurrPos1 = 0.15;
|
||||
public static double redObeliskTurrPos2 = 0.16;
|
||||
public static double redObeliskTurrPos3 = 0.17;
|
||||
public static double blueObeliskTurrPos0 = 0.35;
|
||||
public static double blueObeliskTurrPos1 = -0.15;
|
||||
public static double blueObeliskTurrPos2 = -0.16;
|
||||
public static double blueObeliskTurrPos3 = -0.17;
|
||||
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;
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -5,7 +5,9 @@ import androidx.annotation.NonNull;
|
||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.*;
|
||||
import com.acmerobotics.roadrunner.AccelConstraint;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.Actions;
|
||||
import com.acmerobotics.roadrunner.AngularVelConstraint;
|
||||
import com.acmerobotics.roadrunner.DualNum;
|
||||
import com.acmerobotics.roadrunner.HolonomicController;
|
||||
@@ -14,12 +16,20 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
|
||||
import com.acmerobotics.roadrunner.MotorFeedforward;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.Pose2dDual;
|
||||
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
|
||||
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
|
||||
import com.acmerobotics.roadrunner.ProfileParams;
|
||||
import com.acmerobotics.roadrunner.Rotation2d;
|
||||
import com.acmerobotics.roadrunner.Time;
|
||||
import com.acmerobotics.roadrunner.TimeTrajectory;
|
||||
import com.acmerobotics.roadrunner.TimeTurn;
|
||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
|
||||
import com.acmerobotics.roadrunner.TurnConstraints;
|
||||
import com.acmerobotics.roadrunner.Twist2d;
|
||||
import com.acmerobotics.roadrunner.Twist2dDual;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.VelConstraint;
|
||||
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
|
||||
import com.acmerobotics.roadrunner.ftc.Encoder;
|
||||
@@ -46,13 +56,131 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
|
||||
|
||||
import java.lang.Math;
|
||||
import java.util.Arrays;
|
||||
import java.util.LinkedList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
public final class MecanumDrive {
|
||||
public static Params PARAMS = new Params();
|
||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||
public final VelConstraint defaultVelConstraint =
|
||||
new MinVelConstraint(Arrays.asList(
|
||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||
));
|
||||
public final AccelConstraint defaultAccelConstraint =
|
||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||
public final VoltageSensor voltageSensor;
|
||||
public final LazyImu lazyImu;
|
||||
public final Localizer localizer;
|
||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||
|
||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||
|
||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
//
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||
|
||||
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||
|
||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||
}
|
||||
|
||||
public void setDrivePowers(PoseVelocity2d powers) {
|
||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||
PoseVelocity2dDual.constant(powers, 1));
|
||||
|
||||
double maxPowerMag = 1;
|
||||
for (DualNum<Time> power : wheelVels.all()) {
|
||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||
}
|
||||
|
||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||
}
|
||||
|
||||
public PoseVelocity2d updatePoseEstimate() {
|
||||
PoseVelocity2d vel = localizer.update();
|
||||
poseHistory.add(localizer.getPose());
|
||||
|
||||
while (poseHistory.size() > 100) {
|
||||
poseHistory.removeFirst();
|
||||
}
|
||||
|
||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||
|
||||
return vel;
|
||||
}
|
||||
|
||||
private void drawPoseHistory(Canvas c) {
|
||||
double[] xPoints = new double[poseHistory.size()];
|
||||
double[] yPoints = new double[poseHistory.size()];
|
||||
|
||||
int i = 0;
|
||||
for (Pose2d t : poseHistory) {
|
||||
xPoints[i] = t.position.x;
|
||||
yPoints[i] = t.position.y;
|
||||
|
||||
i++;
|
||||
}
|
||||
|
||||
c.setStrokeWidth(1);
|
||||
c.setStroke("#3F51B5");
|
||||
c.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||
return new TrajectoryActionBuilder(
|
||||
TurnAction::new,
|
||||
FollowTrajectoryAction::new,
|
||||
new TrajectoryBuilderParams(
|
||||
1e-6,
|
||||
new ProfileParams(
|
||||
0.25, 0.1, 1e-2
|
||||
)
|
||||
),
|
||||
beginPose, 0.0,
|
||||
defaultTurnConstraints,
|
||||
defaultVelConstraint, defaultAccelConstraint
|
||||
);
|
||||
}
|
||||
|
||||
public static class Params {
|
||||
// IMU orientation
|
||||
// TODO: fill in these values based on
|
||||
@@ -64,62 +192,33 @@ public final class MecanumDrive {
|
||||
|
||||
// drive model parameters
|
||||
public double inPerTick = 0.001978956;
|
||||
public double lateralInPerTick = 0.0013863732202094405;
|
||||
public double trackWidthTicks = 6488.883015684446;
|
||||
public double lateralInPerTick = 0.001367789463080072;
|
||||
public double trackWidthTicks = 6913.070212622687;
|
||||
|
||||
// feedforward parameters (in tick units)
|
||||
public double kS = 1.2147826978829488;
|
||||
public double kV = 0.00032;
|
||||
public double kA = 0.000046;
|
||||
public double kS = 1.23;
|
||||
public double kV = 0.00035;
|
||||
public double kA = 0.00008;
|
||||
|
||||
// path profile parameters (in inches)
|
||||
public double maxWheelVel = 180;
|
||||
public double maxWheelVel = 70;
|
||||
public double minProfileAccel = -40;
|
||||
public double maxProfileAccel = 180;
|
||||
public double maxProfileAccel = 70;
|
||||
|
||||
// turn profile parameters (in radians)
|
||||
public double maxAngVel = 4* Math.PI; // shared with path
|
||||
public double maxAngAccel = 4* Math.PI;
|
||||
public double maxAngVel = 2 *Math.PI; // shared with path
|
||||
public double maxAngAccel = 2 * Math.PI;
|
||||
|
||||
// path controller gains
|
||||
public double axialGain = 4;
|
||||
public double lateralGain = 4;
|
||||
public double headingGain = 4; // shared with turn
|
||||
public double axialGain = 6.0;
|
||||
public double lateralGain = 6.0;
|
||||
public double headingGain = 6.0; // shared with turn
|
||||
|
||||
public double axialVelGain = 0.0;
|
||||
public double lateralVelGain = 0.0;
|
||||
public double headingVelGain = 0.0; // shared with turn
|
||||
}
|
||||
|
||||
public static Params PARAMS = new Params();
|
||||
|
||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||
|
||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||
public final VelConstraint defaultVelConstraint =
|
||||
new MinVelConstraint(Arrays.asList(
|
||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||
));
|
||||
public final AccelConstraint defaultAccelConstraint =
|
||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||
|
||||
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
|
||||
|
||||
public final VoltageSensor voltageSensor;
|
||||
|
||||
public final LazyImu lazyImu;
|
||||
|
||||
public final Localizer localizer;
|
||||
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
|
||||
|
||||
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
|
||||
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
|
||||
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
|
||||
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
|
||||
|
||||
public class DriveLocalizer implements Localizer {
|
||||
public final Encoder leftFront, leftBack, rightBack, rightFront;
|
||||
public final IMU imu;
|
||||
@@ -144,13 +243,13 @@ public final class MecanumDrive {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setPose(Pose2d pose) {
|
||||
this.pose = pose;
|
||||
public Pose2d getPose() {
|
||||
return pose;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Pose2d getPose() {
|
||||
return pose;
|
||||
public void setPose(Pose2d pose) {
|
||||
this.pose = pose;
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -216,63 +315,10 @@ public final class MecanumDrive {
|
||||
}
|
||||
}
|
||||
|
||||
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
|
||||
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
|
||||
|
||||
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "br");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
|
||||
|
||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
//
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||
|
||||
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
|
||||
|
||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||
}
|
||||
|
||||
public void setDrivePowers(PoseVelocity2d powers) {
|
||||
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
|
||||
PoseVelocity2dDual.constant(powers, 1));
|
||||
|
||||
double maxPowerMag = 1;
|
||||
for (DualNum<Time> power : wheelVels.all()) {
|
||||
maxPowerMag = Math.max(maxPowerMag, power.value());
|
||||
}
|
||||
|
||||
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
|
||||
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
|
||||
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
|
||||
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
|
||||
}
|
||||
|
||||
public final class FollowTrajectoryAction implements Action {
|
||||
public final TimeTrajectory timeTrajectory;
|
||||
private double beginTs = -1;
|
||||
|
||||
private final double[] xPoints, yPoints;
|
||||
private double beginTs = -1;
|
||||
|
||||
public FollowTrajectoryAction(TimeTrajectory t) {
|
||||
timeTrajectory = t;
|
||||
@@ -299,7 +345,16 @@ public final class MecanumDrive {
|
||||
t = Actions.now() - beginTs;
|
||||
}
|
||||
|
||||
if (t >= timeTrajectory.duration) {
|
||||
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
||||
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||
|
||||
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||
|
||||
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||
|
||||
if ((t >= timeTrajectory.duration && error.position.norm() < 1
|
||||
&& robotVelRobot.linearVel.norm() < 0.5)
|
||||
|| t >= timeTrajectory.duration + 0.01) {
|
||||
leftFront.setPower(0);
|
||||
leftBack.setPower(0);
|
||||
rightBack.setPower(0);
|
||||
@@ -308,10 +363,6 @@ public final class MecanumDrive {
|
||||
return false;
|
||||
}
|
||||
|
||||
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
||||
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||
|
||||
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||
|
||||
PoseVelocity2dDual<Time> command = new HolonomicController(
|
||||
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
||||
@@ -342,7 +393,6 @@ public final class MecanumDrive {
|
||||
p.put("y", localizer.getPose().position.y);
|
||||
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
||||
|
||||
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||
p.put("xError", error.position.x);
|
||||
p.put("yError", error.position.y);
|
||||
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
||||
@@ -450,51 +500,4 @@ public final class MecanumDrive {
|
||||
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
|
||||
}
|
||||
}
|
||||
|
||||
public PoseVelocity2d updatePoseEstimate() {
|
||||
PoseVelocity2d vel = localizer.update();
|
||||
poseHistory.add(localizer.getPose());
|
||||
|
||||
while (poseHistory.size() > 100) {
|
||||
poseHistory.removeFirst();
|
||||
}
|
||||
|
||||
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
|
||||
|
||||
|
||||
return vel;
|
||||
}
|
||||
|
||||
private void drawPoseHistory(Canvas c) {
|
||||
double[] xPoints = new double[poseHistory.size()];
|
||||
double[] yPoints = new double[poseHistory.size()];
|
||||
|
||||
int i = 0;
|
||||
for (Pose2d t : poseHistory) {
|
||||
xPoints[i] = t.position.x;
|
||||
yPoints[i] = t.position.y;
|
||||
|
||||
i++;
|
||||
}
|
||||
|
||||
c.setStrokeWidth(1);
|
||||
c.setStroke("#3F51B5");
|
||||
c.strokePolyline(xPoints, yPoints);
|
||||
}
|
||||
|
||||
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
|
||||
return new TrajectoryActionBuilder(
|
||||
TurnAction::new,
|
||||
FollowTrajectoryAction::new,
|
||||
new TrajectoryBuilderParams(
|
||||
1e-6,
|
||||
new ProfileParams(
|
||||
0.25, 0.1, 1e-2
|
||||
)
|
||||
),
|
||||
beginPose, 0.0,
|
||||
defaultTurnConstraints,
|
||||
defaultVelConstraint, defaultAccelConstraint
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -16,10 +16,11 @@ import java.util.Objects;
|
||||
@Config
|
||||
public final class PinpointLocalizer implements Localizer {
|
||||
public static class Params {
|
||||
public double parYTicks = -3765.023079161767; // y position of the parallel encoder (in tick units)
|
||||
public double perpXTicks = -1962.6377639490684; // x position of the perpendicular encoder (in tick units)
|
||||
public double parYTicks = -3758.6603115671537; // y position of the parallel encoder (in tick units)
|
||||
public double perpXTicks = -2088.4296466563774; // x position of the perpendicular encoder (in tick units)
|
||||
}
|
||||
|
||||
|
||||
public static Params PARAMS = new Params();
|
||||
|
||||
public final GoBildaPinpointDriver driver;
|
||||
@@ -48,6 +49,8 @@ public final class PinpointLocalizer implements Localizer {
|
||||
txWorldPinpoint = initialPose;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@Override
|
||||
public void setPose(Pose2d pose) {
|
||||
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
||||
|
||||
@@ -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();
|
||||
}
|
||||
}
|
||||
@@ -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();
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,8 +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.ServoPositions.transferServo_in;
|
||||
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;
|
||||
@@ -10,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;
|
||||
@@ -34,53 +37,57 @@ 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;
|
||||
boolean reject = false;
|
||||
double xOffset = 0.0;
|
||||
double yOffset = 0.0;
|
||||
double headingOffset = 0.0;
|
||||
double hOffset = 0.0;
|
||||
// double headingOffset = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
boolean autoSpintake = false;
|
||||
// boolean autoSpintake = false;
|
||||
boolean enableSpindexerManager = true;
|
||||
|
||||
boolean overrideTurr = false;
|
||||
// boolean overrideTurr = false;
|
||||
|
||||
int intakeTicker = 0;
|
||||
private boolean shootAll = 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) {
|
||||
@@ -90,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();
|
||||
@@ -111,23 +121,36 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
light.setState(StateEnums.LightState.MANUAL);
|
||||
limelightUsed = true;
|
||||
Spindexer.teleop = true;
|
||||
|
||||
robot.light.setPosition(1);
|
||||
while (opModeInInit()) {
|
||||
//ONLY FOR TESTING: COMMENT OUT FOR COMPETITIONS
|
||||
if (gamepad1.crossWasPressed()){
|
||||
redAlliance = !redAlliance;
|
||||
}
|
||||
|
||||
robot.limelight.start();
|
||||
if (redAlliance) {
|
||||
robot.limelight.pipelineSwitch(4);
|
||||
turret.pipelineSwitch(4);
|
||||
light.setManualLightColor(Color.LightRed);
|
||||
predictedResetX = redPredictedResetX;
|
||||
predictedResetY = redPredictedResetY;
|
||||
predictedResetH = Math.toRadians(redPredictedResetH);
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
turret.pipelineSwitch(2);
|
||||
light.setManualLightColor(Color.LightBlue);
|
||||
|
||||
predictedResetX = bluePredictedResetX;
|
||||
predictedResetY = bluePredictedResetY;
|
||||
predictedResetH = Math.toRadians(bluePredictedResetH);
|
||||
}
|
||||
limelightUsed = true;
|
||||
|
||||
TELE.addData("Red Alliance?", redAlliance);
|
||||
TELE.update();
|
||||
|
||||
light.update();
|
||||
}
|
||||
|
||||
limelightUsed = true;
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
@@ -138,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:
|
||||
|
||||
@@ -155,35 +234,55 @@ 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);
|
||||
//}
|
||||
} else {
|
||||
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||
}
|
||||
|
||||
//TURRET TRACKING
|
||||
|
||||
double robX = drive.localizer.getPose().position.x;
|
||||
double robY = drive.localizer.getPose().position.y;
|
||||
double robX = currentPose.getX();
|
||||
double robY = currentPose.getY();
|
||||
double robH = currentPose.getHeading();
|
||||
|
||||
double robotX = robX - xOffset;
|
||||
double robotY = robY - yOffset;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
double robotX = robX + xOffset;
|
||||
double robotY = robY + yOffset;
|
||||
double robotHeading = robH + hOffset;
|
||||
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
// 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 dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
|
||||
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
//RELOCALIZATION
|
||||
|
||||
if (gamepad2.triangleWasPressed()){
|
||||
relocalize = !relocalize;
|
||||
gamepad2.rumble(500);
|
||||
}
|
||||
|
||||
if (relocalize){
|
||||
turret.relocalize();
|
||||
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);
|
||||
}
|
||||
|
||||
//VELOCITY AUTOMATIC
|
||||
if (autoVel) {
|
||||
@@ -210,7 +309,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//SHOOTER:
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
|
||||
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||
flywheel.manageFlywheel(vel);
|
||||
|
||||
//HOOD:
|
||||
@@ -247,72 +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()) {
|
||||
servo.setTransferPos(transferServo_in);
|
||||
//TELE.addLine("shoot");
|
||||
} else {
|
||||
servo.setTransferPos(transferServo_out);
|
||||
//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();
|
||||
@@ -345,18 +391,22 @@ public class TeleopV3 extends LinearOpMode {
|
||||
// Targeting Debug
|
||||
TELE.addData("robotX", robotX);
|
||||
TELE.addData("robotY", robotY);
|
||||
TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||
TELE.addData("robotInchesY", targeting.robotInchesY);
|
||||
TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||
TELE.addData("robot H", robotHeading);
|
||||
// TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||
// TELE.addData("robotInchesY", targeting.robotInchesY);
|
||||
// TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||
TELE.addData("Targeting GridX", targeting.robotGridX);
|
||||
TELE.addData("Targeting GridY", targeting.robotGridY);
|
||||
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
||||
// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||
// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||
// TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
||||
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.update();
|
||||
|
||||
|
||||
@@ -0,0 +1,126 @@
|
||||
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;
|
||||
VelocityCommander commander;
|
||||
|
||||
ParkTilter parkTilter;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot.resetInstance();
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
follower.setStartingPose(start);
|
||||
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
|
||||
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
//Drivetrain
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x
|
||||
);
|
||||
|
||||
follower.update();
|
||||
|
||||
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if (gamepad1.leftBumperWasPressed() &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
|
||||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_IN ||
|
||||
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
|
||||
}
|
||||
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.INTAKE
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", robot.transfer.getPower());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -7,6 +7,7 @@ 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.NormalizedRGBA;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
@@ -28,16 +29,20 @@ public class ColorTest extends LinearOpMode {
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while(opModeIsActive()){
|
||||
double green1 = robot.color1.getNormalizedColors().green;
|
||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||
double red1 = robot.color1.getNormalizedColors().red;
|
||||
|
||||
|
||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||
|
||||
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||
|
||||
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
||||
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
||||
|
||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||
TELE.addData("Color1 green", gP1);
|
||||
TELE.addData("Color1 distance (mm)", color1Distance);
|
||||
|
||||
|
||||
// ----- COLOR 2 -----
|
||||
double green2 = robot.color2.getNormalizedColors().green;
|
||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
@@ -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.CM));
|
||||
TELE.addData("REV Green", revColor.green / (revColor.red + revColor.blue + revColor.green));
|
||||
|
||||
TELE.addData("Voltage Sensor", robot.voltage.getVoltage());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,131 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.pedropathing.follower.Follower;
|
||||
import com.pedropathing.geometry.Pose;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.*;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class NewShooterTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
Drivetrain drivetrain;
|
||||
Shooter shooter;
|
||||
MultipleTelemetry TELE;
|
||||
Follower follower;
|
||||
SpindexerTransferIntake spindexerTransferIntake;
|
||||
Turret turret;
|
||||
Flywheel flywheel;
|
||||
VelocityCommander commander;
|
||||
ParkTilter parkTilter;
|
||||
|
||||
public static int flywheelVelo = 0;
|
||||
public static double hoodPos = 0.5;
|
||||
public static double transferPower = -0.7;
|
||||
// public static double turretPos = 0.51;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot.resetInstance();
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
follower.setStartingPose(start);
|
||||
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
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
|
||||
);
|
||||
|
||||
follower.update();
|
||||
|
||||
shooter.setFlywheelVelocity(flywheelVelo);
|
||||
robot.setHoodPos(hoodPos);
|
||||
// shooter.setTurretPosition(turretPos);
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if (gamepad1.leftBumperWasPressed() &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
|
||||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_IN ||
|
||||
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
|
||||
}
|
||||
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.INTAKE
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", commander.getTransferPow());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -2,18 +2,19 @@ package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.teleop.TeleopV3.spinSpeedIncrease;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.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;
|
||||
@@ -37,7 +38,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
public static double P = 255.0;
|
||||
public static double I = 0.0;
|
||||
public static double D = 0.0;
|
||||
public static double F = 90;
|
||||
public static double F = 75;
|
||||
public static double transferPower = 1.0;
|
||||
public static double hoodPos = 0.501;
|
||||
public static double turretPos = 0.501;
|
||||
@@ -106,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);
|
||||
|
||||
@@ -128,9 +129,9 @@ public class ShooterTest extends LinearOpMode {
|
||||
|
||||
if (hoodPos != 0.501) {
|
||||
if (enableHoodAutoOpen) {
|
||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)) + hoodOffset);
|
||||
} else {
|
||||
robot.hood.setPosition(hoodPos);
|
||||
robot.hood.setPosition(hoodPos + hoodOffset);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,141 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.pedropathing.follower.Follower;
|
||||
import com.pedropathing.geometry.Pose;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.*;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class SortedSpindexerTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
Drivetrain drivetrain;
|
||||
Shooter shooter;
|
||||
MultipleTelemetry TELE;
|
||||
Follower follower;
|
||||
SpindexerTransferIntake spindexerTransferIntake;
|
||||
Turret turret;
|
||||
Flywheel flywheel;
|
||||
VelocityCommander commander;
|
||||
|
||||
ParkTilter parkTilter;
|
||||
public static String order = "GPP";
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot.resetInstance();
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
follower.setStartingPose(start);
|
||||
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SORTED);
|
||||
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
|
||||
switch(order) {
|
||||
case "PPG":
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.PPG
|
||||
);
|
||||
break;
|
||||
|
||||
case "PGP":
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.PGP
|
||||
);
|
||||
break;
|
||||
|
||||
default:
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.GPP
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
//Drivetrain
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x
|
||||
);
|
||||
|
||||
follower.update();
|
||||
|
||||
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if(gamepad1.leftBumperWasPressed()) {
|
||||
spindexerTransferIntake.startSortedShoot();
|
||||
}
|
||||
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.INTAKE
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", robot.transfer.getPower());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,115 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.autonomous.actions.AutoActions;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class SortingTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
Servos servos;
|
||||
Spindexer spindexer;
|
||||
Flywheel flywheel;
|
||||
Turret turret;
|
||||
Targeting targeting;
|
||||
Targeting.Settings targetingSettings;
|
||||
AutoActions autoActions;
|
||||
Light light;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
targeting = new Targeting();
|
||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
servos = new Servos(hardwareMap);
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||
|
||||
light = Light.getInstance();
|
||||
|
||||
light.init(robot.light, spindexer, turret);
|
||||
|
||||
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
||||
|
||||
int motif = 21;
|
||||
boolean intaking = true;
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
|
||||
if (opModeIsActive()){
|
||||
Actions.runBlocking(
|
||||
autoActions.ShakeDrivetrain(
|
||||
100
|
||||
)
|
||||
);
|
||||
// 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();
|
||||
// }
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -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();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -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;
|
||||
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;
|
||||
|
||||
@@ -12,15 +12,13 @@ public class Flywheel {
|
||||
public double velo1 = 0.0;
|
||||
public double velo2 = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
double previousTargetVelocity = 0.0;
|
||||
double powPID = 0.0;
|
||||
boolean steady = false;
|
||||
public Flywheel (HardwareMap hardwareMap) {
|
||||
robot = new Robot(hardwareMap);
|
||||
shooterPIDF1 = new PIDFCoefficients
|
||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
|
||||
shooterPIDF2 = new PIDFCoefficients
|
||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
|
||||
}
|
||||
|
||||
public double getVelo () {
|
||||
@@ -38,8 +36,8 @@ public class Flywheel {
|
||||
}
|
||||
|
||||
// Set the robot PIDF for the next cycle.
|
||||
private double prevF = 0.501;
|
||||
public static int voltagePIDFDifference = 5;
|
||||
private double prevF = 0;
|
||||
public static double voltagePIDFDifference = 0.8;
|
||||
public void setPIDF(double p, double i, double d, double f) {
|
||||
shooterPIDF1.p = p;
|
||||
shooterPIDF1.i = i;
|
||||
@@ -52,6 +50,7 @@ public class Flywheel {
|
||||
if (Math.abs(prevF - f) > voltagePIDFDifference){
|
||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||
prevF = f;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -61,26 +60,23 @@ public class Flywheel {
|
||||
// Convert from Ticks per Second to RPM
|
||||
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||
|
||||
public double manageFlywheel(double commandedVelocity) {
|
||||
public void manageFlywheel(double commandedVelocity) {
|
||||
|
||||
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
|
||||
targetVelocity = commandedVelocity;
|
||||
// Add code here to set PIDF based on desired RPM
|
||||
//robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||
//robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
|
||||
// Record Current Velocity
|
||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||
velo = Math.max(velo1, velo2);
|
||||
|
||||
}
|
||||
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||
velo = Math.max(velo1, velo2);
|
||||
// really should be a running average of the last 5
|
||||
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
||||
steady = (Math.abs(commandedVelocity - velo) < 50);
|
||||
|
||||
return powPID;
|
||||
}
|
||||
|
||||
public void update()
|
||||
|
||||
@@ -12,7 +12,7 @@ public final class Light {
|
||||
|
||||
private static Light instance;
|
||||
public static double ballColorCycleTime = 1000; //in ms
|
||||
public static double restingTime = 150; //in ms
|
||||
public static double restingTime = 125; //in ms
|
||||
|
||||
private Servo lightServo;
|
||||
private LightState state = LightState.DISABLED;
|
||||
@@ -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 {
|
||||
|
||||
@@ -7,10 +7,10 @@ public class MeasuringLoopTimes {
|
||||
private double minLoopTime = 999999999999.0;
|
||||
|
||||
private double maxLoopTime = 0.0;
|
||||
private double mainLoopTime = 0.0;
|
||||
double mainLoopTime = 0.0;
|
||||
|
||||
private double MeasurementStart = 0.0;
|
||||
private double currentTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
|
||||
private double avgLoopTime = 0.0;
|
||||
private int avgLoopTimeTicker = 0;
|
||||
@@ -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;
|
||||
|
||||
@@ -1,17 +1,16 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.arcrobotics.ftclib.hardware.ServoEx;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
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;
|
||||
@@ -31,21 +30,31 @@ public class Robot {
|
||||
public DcMotorEx intake;
|
||||
public DcMotorEx transfer;
|
||||
public PIDFCoefficients shooterPIDF;
|
||||
public double shooterPIDF_P = 255.0;
|
||||
public double shooterPIDF_I = 0.0;
|
||||
public double shooterPIDF_D = 0.0;
|
||||
public double shooterPIDF_F = 90;
|
||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||
public 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;
|
||||
// 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 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;
|
||||
@@ -57,7 +66,6 @@ public class Robot {
|
||||
public RevColorSensorV3 color3;
|
||||
public Limelight3A limelight;
|
||||
public Servo light;
|
||||
public VoltageSensor voltage;
|
||||
|
||||
public Robot(HardwareMap hardwareMap) {
|
||||
|
||||
@@ -75,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");
|
||||
|
||||
@@ -91,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");
|
||||
@@ -127,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;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
@@ -12,8 +14,6 @@ public class Servos {
|
||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||
public static double spin_scalar = 1.112;
|
||||
public static double spin_restPos = 0.155;
|
||||
public static double turret_scalar = 1.009;
|
||||
public static double turret_restPos = 0.0;
|
||||
Robot robot;
|
||||
PIDFController spinPID;
|
||||
PIDFController turretPID;
|
||||
@@ -49,14 +49,13 @@ public class Servos {
|
||||
return (Math.abs(pos1 - pos2) < 0.005);
|
||||
}
|
||||
|
||||
public double setTransferPos(double pos) {
|
||||
public void setTransferPos(double pos) {
|
||||
if (firstTransferPos || !servoPosEqual(pos, prevTransferPos)) {
|
||||
robot.transferServo.setPosition(pos);
|
||||
firstTransferPos = false;
|
||||
}
|
||||
|
||||
prevTransferPos = pos;
|
||||
return pos;
|
||||
}
|
||||
|
||||
public double setSpinPos(double pos) {
|
||||
@@ -70,29 +69,16 @@ public class Servos {
|
||||
return pos;
|
||||
}
|
||||
|
||||
public double setHoodPos(double pos){
|
||||
public void setHoodPos(double pos){
|
||||
if (firstHoodPos || !servoPosEqual(pos, prevHoodPos)) {
|
||||
robot.hood.setPosition(pos);
|
||||
robot.hood.setPosition(pos + hoodOffset);
|
||||
firstHoodPos = false;
|
||||
}
|
||||
|
||||
prevHoodPos = pos;
|
||||
return pos;
|
||||
}
|
||||
|
||||
public boolean spinEqual(double pos) {
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return 1.0;
|
||||
}
|
||||
|
||||
public double setTurrPos(double pos) {
|
||||
return 1.0;
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return true;
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.05;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -16,6 +16,8 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||
@@ -46,12 +48,15 @@ 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;
|
||||
public double spindexerPosOffset = 0.00;
|
||||
public static int shootWaitMax = 4;
|
||||
public static boolean whileShooting = false;
|
||||
public static int waitFirstBallTicks = 4;
|
||||
private int shootTicks = 0;
|
||||
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
||||
// For Use
|
||||
enum RotatedBallPositionNames {
|
||||
@@ -168,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);
|
||||
@@ -182,12 +202,12 @@ public class Spindexer {
|
||||
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
||||
|
||||
// Position 1
|
||||
if (distanceRearCenter < 60) {
|
||||
if (distanceRearCenter < rearDistance) {
|
||||
|
||||
// Mark Ball Found
|
||||
newPos1Detection = true;
|
||||
|
||||
if (detectRearColor) {
|
||||
if (detectRearColor && !teleop) {
|
||||
// Detect which color
|
||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||
|
||||
@@ -204,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 < 56) {
|
||||
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);
|
||||
@@ -230,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);
|
||||
@@ -362,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
|
||||
@@ -373,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) {
|
||||
@@ -381,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
|
||||
@@ -392,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
|
||||
@@ -423,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:
|
||||
@@ -452,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:
|
||||
@@ -531,20 +557,26 @@ public class Spindexer {
|
||||
|
||||
case SHOOT_PREP_CONTINOUS:
|
||||
if (servos.spinEqual(spinStartPos)){
|
||||
servos.setTransferPos(transferServo_in);
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
||||
} else {
|
||||
servos.setTransferPos(transferServo_out);
|
||||
servos.setSpinPos(spinStartPos);
|
||||
}
|
||||
break;
|
||||
|
||||
case SHOOT_CONTINOUS:
|
||||
whileShooting = true;
|
||||
ballPositions[0].isEmpty = false;
|
||||
ballPositions[1].isEmpty = false;
|
||||
ballPositions[2].isEmpty = false;
|
||||
if (servos.getSpinPos() > spinEndPos){
|
||||
whileShooting = false;
|
||||
servos.setTransferPos(transferServo_out);
|
||||
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;
|
||||
}
|
||||
|
||||
@@ -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,24 +85,64 @@ public class Targeting {
|
||||
public Targeting() {
|
||||
}
|
||||
|
||||
//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);
|
||||
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));
|
||||
// }
|
||||
|
||||
double cos45 = Math.cos(Math.toRadians(-45));
|
||||
double sin45 = Math.sin(Math.toRadians(-45));
|
||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
||||
// 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));
|
||||
|
||||
// Convert robot coordinates to inches
|
||||
robotInchesX = rotatedX * unitConversionFactor;
|
||||
robotInchesY = rotatedY * unitConversionFactor;
|
||||
|
||||
// Find approximate location in the grid
|
||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||
|
||||
int remX = Math.floorMod((int) robotInchesX, tileSize);
|
||||
int remY = Math.floorMod((int) robotInchesX, tileSize);
|
||||
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.
|
||||
@@ -172,21 +215,11 @@ public class Targeting {
|
||||
interpolate = false;
|
||||
}
|
||||
|
||||
//clamp
|
||||
|
||||
if (redAlliance) {
|
||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||
} else {
|
||||
robotGridY = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||
robotGridX = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||
}
|
||||
|
||||
// basic search
|
||||
if (true) { //!interpolate) {
|
||||
if ((robotGridY < 6) && (robotGridX < 6)) {
|
||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle + ServoPositions.hoodOffset;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle + hoodOffset;
|
||||
}
|
||||
return recommendedSettings;
|
||||
} else {
|
||||
|
||||
@@ -6,15 +6,17 @@ 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;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.teleop.TeleopV3;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@@ -23,23 +25,21 @@ public class Turret {
|
||||
|
||||
public static double turretTolerance = 0.02;
|
||||
public static double turrPosScalar = 0.00011264432;
|
||||
public static double turret180Range = 0.4;
|
||||
public static double turrDefault = 0.39;
|
||||
public static double turrMin = 0.15;
|
||||
public static double turrMax = 0.85;
|
||||
public static 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;
|
||||
|
||||
public static double visionCorrectionGain = 0.08; // Single tunable gain
|
||||
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
||||
public static double cameraBearingEqual = 0.5; // Deadband
|
||||
// public static double visionCorrectionGain = 0.08; // Single tunable gain
|
||||
// public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
||||
// public static double cameraBearingEqual = 0.5; // Deadband
|
||||
|
||||
// TODO: tune these values for limelight
|
||||
|
||||
public static double clampTolerance = 0.03;
|
||||
// public static double clampTolerance = 0.03;
|
||||
//public static double B_PID_P = 0.105, B_PID_I = 0.0, B_PID_D = 0.0125;
|
||||
public static double B_PID_P = 0.066, B_PID_I = 0.0, B_PID_D = 0.007;
|
||||
public static double B_PID_P = 0.08, B_PID_I = 0.0, B_PID_D = 0.007;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Limelight3A webcam;
|
||||
@@ -48,6 +48,8 @@ public class Turret {
|
||||
double limelightPosX = 0.0;
|
||||
double limelightPosY = 0.0;
|
||||
LLResult result;
|
||||
public static double TARGET_POSITION_TOLERANCE = 0.5;
|
||||
public static double COLOR_OK_TOLERANCE = 2;
|
||||
boolean bearingAligned = false;
|
||||
private boolean lockOffset = false;
|
||||
private int obeliskID = 0;
|
||||
@@ -55,11 +57,12 @@ public class Turret {
|
||||
private double currentTrackOffset = 0.0;
|
||||
private double lightColor = Color.LightRed;
|
||||
private int currentTrackCount = 0;
|
||||
private double permanentOffset = 0.0;
|
||||
private PIDController bearingPID;
|
||||
double permanentOffset = 0.0;
|
||||
private int prevPipeline = -1;
|
||||
PIDController bearingPID;
|
||||
|
||||
private double prevTurretPos = 0.0;
|
||||
private boolean firstTurretPos = true;
|
||||
public int llCoast = 0;
|
||||
public int LL_COAST_TICKS = 60;
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||
this.TELE = tele;
|
||||
@@ -78,36 +81,52 @@ public class Turret {
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
||||
return robot.turr1.getPosition();
|
||||
|
||||
}
|
||||
private double prevTurrPos = 0.501;
|
||||
private double prevTurrPos = 0;
|
||||
private boolean isFirstTurretPos = true;
|
||||
public void setTurret(double pos) {
|
||||
if (prevTurrPos != 0.501 && prevTurrPos != pos){
|
||||
if (isFirstTurretPos || prevTurrPos != pos){
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1-pos);
|
||||
isFirstTurretPos = false;
|
||||
}
|
||||
prevTurrPos = pos;
|
||||
}
|
||||
public void pipelineSwitch(int pipeline){
|
||||
if (prevPipeline != pipeline){
|
||||
robot.limelight.pipelineSwitch(pipeline);
|
||||
}
|
||||
prevPipeline = pipeline;
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||
}
|
||||
|
||||
public static double alphaPosConstant = 0.3;
|
||||
private void limelightRead() { // only for tracking purposes, not general reads
|
||||
|
||||
Double xPos = null;
|
||||
Double yPos = 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;
|
||||
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);
|
||||
limelightTagH = (alphaPosConstant * hPos) + ((1 - alphaPosConstant) * limelightTagH);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -122,12 +141,20 @@ public class Turret {
|
||||
return ty;
|
||||
}
|
||||
|
||||
double limelightTagX = 0.0;
|
||||
double limelightTagY = 0.0;
|
||||
double limelightTagZ = 0.0;
|
||||
double limelightTagH = 0.0;
|
||||
public double getLimelightX() {
|
||||
return limelightPosX;
|
||||
return limelightTagX;
|
||||
}
|
||||
public double getLimelightY() {return limelightTagY;}
|
||||
public double getLimelightZ(){return limelightTagZ;}
|
||||
public double getLimelightH(){return limelightTagH;}
|
||||
|
||||
public double getLimelightY() {
|
||||
return limelightPosY;
|
||||
public void relocalize(){
|
||||
setTurret(turrDefault);
|
||||
limelightRead();
|
||||
}
|
||||
|
||||
public int detectObelisk() {
|
||||
@@ -135,8 +162,12 @@ public class Turret {
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
double prevTx = -1000;
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
double currentTx = fiducial.getTargetXDegrees();
|
||||
if (currentTx > prevTx){
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
}
|
||||
}
|
||||
}
|
||||
return obeliskID;
|
||||
@@ -157,16 +188,16 @@ public class Turret {
|
||||
/*
|
||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||
*/
|
||||
|
||||
private double targetTx = 0;
|
||||
public static double alphaTX = 0.5;
|
||||
private double bearingAlign(LLResult llResult) {
|
||||
double bearingOffset = 0.0;
|
||||
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
|
||||
final double MIN_OFFSET_POWER = 0.15;
|
||||
final double TARGET_POSITION_TOLERANCE = 1.0;
|
||||
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
||||
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
||||
final double DRIVE_POWER_REDUCTION = 2.0;
|
||||
final double COLOR_OK_TOLERANCE = 2.5;
|
||||
double tx = llResult.getTx(); // How far left or right the target is (degrees)
|
||||
targetTx = (tx*alphaTX)+(targetTx*(1-alphaTX));
|
||||
// final double MIN_OFFSET_POWER = 0.15;
|
||||
// // LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
||||
// final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
||||
// final double DRIVE_POWER_REDUCTION = 2.0;
|
||||
|
||||
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
||||
bearingAligned = true;
|
||||
@@ -202,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;
|
||||
@@ -230,11 +275,18 @@ public class Turret {
|
||||
|
||||
turretAngleDeg += permanentOffset;
|
||||
|
||||
|
||||
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++;
|
||||
|
||||
TELE.addData("LL Tracking: ", llCoast);
|
||||
|
||||
// Assume the last tracked value is always better than
|
||||
// any previous value, even if its not fully aligned.
|
||||
llCoast = LL_COAST_TICKS;
|
||||
// double bearingError = Math.abs(tagBearingDeg);
|
||||
//
|
||||
// if (bearingError > cameraBearingEqual) {
|
||||
@@ -265,9 +317,15 @@ public class Turret {
|
||||
// if (currentTrackCount > 20) {
|
||||
// offset = currentTrackOffset;
|
||||
// }
|
||||
lightColor = Color.LightRed;
|
||||
currentTrackOffset = 0.0;
|
||||
currentTrackCount = 0;
|
||||
if (llCoast <= 0) {
|
||||
TELE.addData("LL No Track: ", llCoast);
|
||||
lightColor = Color.LightRed;
|
||||
currentTrackOffset = 0.0;
|
||||
currentTrackCount = 0;
|
||||
} else {
|
||||
TELE.addData("LL Coasting: ", llCoast);
|
||||
llCoast--;
|
||||
}
|
||||
}
|
||||
|
||||
// Apply accumulated offset
|
||||
@@ -276,13 +334,13 @@ 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));
|
||||
|
||||
// Interpolate towards target position
|
||||
double currentPos = getTurrPos();
|
||||
// double currentPos = getTurrPos();
|
||||
double turretPos = targetTurretPos;
|
||||
|
||||
if (targetTurretPos == turrMin) {
|
||||
@@ -292,20 +350,23 @@ public class Turret {
|
||||
}
|
||||
|
||||
// Set servo positions
|
||||
setTurret(turretPos + manualOffset);
|
||||
if (!Spindexer.whileShooting || abs(targetTx) > COLOR_OK_TOLERANCE){
|
||||
setTurret(turretPos + manualOffset);
|
||||
}
|
||||
|
||||
|
||||
/* ---------------- TELEMETRY ---------------- */
|
||||
|
||||
// TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
|
||||
// TELE.addData("Target Pos", "%.3f", targetTurretPos);
|
||||
// TELE.addData("Current Pos", "%.3f", currentPos);
|
||||
// TELE.addData("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();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,137 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
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;
|
||||
|
||||
@Config
|
||||
public class Flywheel {
|
||||
Robot robot;
|
||||
|
||||
// public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||
public static PIDFCoefficients shooterPIDF;
|
||||
public static double shooterPIDF_P = 500;
|
||||
public static double shooterPIDF_I = 1;
|
||||
public static double shooterPIDF_D = 0.0;
|
||||
public static double shooterPIDF_F = 93;
|
||||
|
||||
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 = 1;
|
||||
public void setF(double voltage){
|
||||
double f = shooterPIDF_F / voltage;
|
||||
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;}
|
||||
}
|
||||
@@ -0,0 +1,22 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
|
||||
public class ParkTilter {
|
||||
Robot robot;
|
||||
public ParkTilter (Robot rob) {
|
||||
this.robot = rob;
|
||||
}
|
||||
|
||||
public void park() {
|
||||
robot.setTilt1Pos(ServoPositions.tilt1_down);
|
||||
robot.setTilt2Pos(ServoPositions.tilt2_down);
|
||||
}
|
||||
|
||||
public void unpark() {
|
||||
robot.setTilt1Pos(ServoPositions.tilt1_up);
|
||||
robot.setTilt2Pos(ServoPositions.tilt2_up);
|
||||
}
|
||||
}
|
||||
@@ -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 = 3;
|
||||
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;
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,213 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.utilsv2.Flywheel.*;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.pedropathing.follower.Follower;
|
||||
|
||||
@Config
|
||||
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;
|
||||
double turretGoalX = 0;
|
||||
double turretGoalY = 0;
|
||||
|
||||
private boolean red = true;
|
||||
public static boolean manualFlywheel = false;
|
||||
|
||||
|
||||
Follower follow;
|
||||
|
||||
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel, VelocityCommander com) {
|
||||
this.robot = rob;
|
||||
this.fly = flywheel;
|
||||
this.turr = turret;
|
||||
this.follow = follower;
|
||||
this.commander = com;
|
||||
|
||||
setRedAlliance(redAlliance);
|
||||
|
||||
}
|
||||
|
||||
public void setRedAlliance(boolean input) {
|
||||
this.red = input;
|
||||
|
||||
if (this.red) {
|
||||
goalX = 144;
|
||||
turretGoalX = 136;
|
||||
} else {
|
||||
goalX = 0;
|
||||
turretGoalX = 8;
|
||||
}
|
||||
goalY = 144;
|
||||
turretGoalY = 136;
|
||||
}
|
||||
|
||||
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();
|
||||
}
|
||||
|
||||
private final double shooterDistFromCenter = 1.545;
|
||||
public void update(double voltage) {
|
||||
|
||||
switch (state) {
|
||||
case NOTHING:
|
||||
break;
|
||||
case MANUAL:
|
||||
manualFlywheel = true;
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
|
||||
turr.manual(turretPosition);
|
||||
break;
|
||||
case TRACK_GOAL:
|
||||
manualFlywheel = false;
|
||||
turr.trackGoal(
|
||||
(turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading(),
|
||||
follow.getAngularVelocity(),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
);
|
||||
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
|
||||
robot.setHoodPos(commander.getHoodPredicted());
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
case READ_OBELISK:
|
||||
manualFlywheel = false;
|
||||
turr.trackObelisk(
|
||||
(obeliskX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(obeliskY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading()
|
||||
);
|
||||
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
|
||||
case MANUAL_TURRET_TRACK_FLY:
|
||||
manualFlywheel = false;
|
||||
turr.manual(turretPosition);
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
robot.setHoodPos(commander.getHoodPredicted());
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
break;
|
||||
|
||||
case MANUAL_FLYWHEEL_TRACK_TURR:
|
||||
manualFlywheel = true;
|
||||
turr.trackGoal(
|
||||
(turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading(),
|
||||
follow.getAngularVelocity(),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
);
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public double getDistance(){return commander.getDistance();}
|
||||
|
||||
|
||||
}
|
||||
@@ -0,0 +1,692 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import android.health.connect.datatypes.units.Velocity;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
import org.firstinspires.ftc.teamcode.tests.NewShooterTest;
|
||||
|
||||
@Config
|
||||
public class SpindexerTransferIntake {
|
||||
|
||||
private final Robot robot;
|
||||
|
||||
VelocityCommander commander;
|
||||
|
||||
private MultipleTelemetry TELE;
|
||||
|
||||
public SpindexerTransferIntake(Robot rob, MultipleTelemetry tele, VelocityCommander com) {
|
||||
this.robot = rob;
|
||||
this.commander = com;
|
||||
this.TELE = tele;
|
||||
}
|
||||
|
||||
public enum DesiredPattern {
|
||||
PPG,
|
||||
PGP,
|
||||
GPP
|
||||
}
|
||||
|
||||
public enum SortedShootState {
|
||||
IDLE,
|
||||
|
||||
MOVE_TO_1,
|
||||
WAIT_FOR_1,
|
||||
SHOOT_1,
|
||||
RETRACT_1,
|
||||
|
||||
MOVE_TO_2,
|
||||
WAIT_FOR_2,
|
||||
SHOOT_2,
|
||||
RETRACT_2,
|
||||
|
||||
MOVE_TO_3,
|
||||
WAIT_FOR_3,
|
||||
SHOOT_3,
|
||||
RETRACT_3,
|
||||
|
||||
DONE
|
||||
}
|
||||
|
||||
int[] shootOrder = {0, 1, 2};
|
||||
private final double sensorDistanceThreshold = 6.0;
|
||||
private final long pulseTime = 100; // ms
|
||||
|
||||
private DesiredPattern desiredPattern = DesiredPattern.GPP;
|
||||
|
||||
private SortedShootState shootState = SortedShootState.IDLE;
|
||||
private long shootStateStartTime = System.currentTimeMillis();
|
||||
|
||||
private void setShootState(SortedShootState newState) {
|
||||
shootState = newState;
|
||||
shootStateStartTime = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
private long shootStateTime() {
|
||||
return System.currentTimeMillis() - shootStateStartTime;
|
||||
}
|
||||
|
||||
private int[] buildShootOrder(
|
||||
BallStates[] loaded,
|
||||
DesiredPattern desired) {
|
||||
|
||||
BallStates[] target;
|
||||
|
||||
switch (desired) {
|
||||
case PPG:
|
||||
target = new BallStates[]{
|
||||
BallStates.PURPLE,
|
||||
BallStates.PURPLE,
|
||||
BallStates.GREEN
|
||||
};
|
||||
break;
|
||||
|
||||
case PGP:
|
||||
target = new BallStates[]{
|
||||
BallStates.PURPLE,
|
||||
BallStates.GREEN,
|
||||
BallStates.PURPLE
|
||||
};
|
||||
break;
|
||||
|
||||
default: // GPP
|
||||
target = new BallStates[]{
|
||||
BallStates.GREEN,
|
||||
BallStates.PURPLE,
|
||||
BallStates.PURPLE
|
||||
};
|
||||
}
|
||||
|
||||
int[] order = new int[3];
|
||||
boolean[] used = new boolean[3];
|
||||
|
||||
// first pass: exact color matches
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
||||
order[i] = -1;
|
||||
|
||||
for (int slot = 0; slot < 3; slot++) {
|
||||
|
||||
if (!used[slot]
|
||||
&& loaded[slot] == target[i]) {
|
||||
|
||||
order[i] = slot;
|
||||
used[slot] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// second pass: fill leftovers
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
||||
if (order[i] != -1)
|
||||
continue;
|
||||
|
||||
for (int slot = 0; slot < 3; slot++) {
|
||||
|
||||
if (!used[slot]) {
|
||||
order[i] = slot;
|
||||
used[slot] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return order;
|
||||
}
|
||||
|
||||
private void moveToSlot(int slot) {
|
||||
|
||||
switch (slot) {
|
||||
|
||||
case 0:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A2
|
||||
);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A3
|
||||
);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
public enum SortedIntakeStates {
|
||||
NOTHING,
|
||||
IDLE,
|
||||
INTAKE_1,
|
||||
DELAY_1,
|
||||
INTAKE_2,
|
||||
DELAY_2,
|
||||
INTAKE_3,
|
||||
REVERSE,
|
||||
|
||||
}
|
||||
|
||||
public enum SpindexerMode {
|
||||
RAPID,
|
||||
SORTED,
|
||||
SHOOT_SORTED
|
||||
}
|
||||
|
||||
public enum BallStates {
|
||||
GREEN,
|
||||
PURPLE,
|
||||
UNKNOWN
|
||||
}
|
||||
|
||||
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;
|
||||
private SortedIntakeStates sortedIntakeStates = SortedIntakeStates.IDLE;
|
||||
private BallStates[] ballColors = {BallStates.UNKNOWN, BallStates.UNKNOWN, BallStates.UNKNOWN};
|
||||
private final double greenThresh = 0.39;
|
||||
private final double spinMovementTime = 250;
|
||||
|
||||
/**
|
||||
* Time when current state was entered.
|
||||
*/
|
||||
private long stateStartTime = System.currentTimeMillis();
|
||||
private long sortedStateStartTime = System.currentTimeMillis();
|
||||
|
||||
public void setDesiredPattern(DesiredPattern pattern) {
|
||||
desiredPattern = pattern;
|
||||
}
|
||||
|
||||
public void startSortedShoot() {
|
||||
|
||||
shootOrder = buildShootOrder(
|
||||
ballColors,
|
||||
desiredPattern
|
||||
);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.IDLE
|
||||
);
|
||||
|
||||
setSpindexerMode(
|
||||
SpindexerMode.SHOOT_SORTED
|
||||
);
|
||||
}
|
||||
public void setRapidMode(RapidMode newMode) {
|
||||
if (rapidMode != newMode) {
|
||||
rapidMode = newMode;
|
||||
stateStartTime = System.currentTimeMillis();
|
||||
}
|
||||
}
|
||||
|
||||
public void setSortedIntakeMode(SortedIntakeStates newMode) {
|
||||
if (sortedIntakeStates != newMode) {
|
||||
sortedIntakeStates = newMode;
|
||||
sortedStateStartTime = System.currentTimeMillis();
|
||||
}
|
||||
}
|
||||
|
||||
public void setSpindexerMode(SpindexerMode spindexerMode) {
|
||||
this.mode = spindexerMode;
|
||||
}
|
||||
|
||||
public RapidMode getRapidState() {
|
||||
return this.rapidMode;
|
||||
}
|
||||
|
||||
private long stateTime() {
|
||||
return System.currentTimeMillis() - stateStartTime;
|
||||
}
|
||||
|
||||
private long sortedStateTime() {
|
||||
return System.currentTimeMillis() - sortedStateStartTime;
|
||||
}
|
||||
|
||||
public void update() {
|
||||
|
||||
TELE.addData("Sorted State", sortedIntakeStates);
|
||||
TELE.addData("Ball0", ballColors[0]);
|
||||
TELE.addData("Ball1", ballColors[1]);
|
||||
TELE.addData("Ball2", ballColors[2]);
|
||||
|
||||
TELE.addData("Shoot0", shootOrder[0]);
|
||||
TELE.addData("Shoot1", shootOrder[1]);
|
||||
TELE.addData("Shoot2", shootOrder[2]);
|
||||
|
||||
TELE.addData("Color0", ballColors[0]);
|
||||
TELE.addData("Color1", ballColors[1]);
|
||||
TELE.addData("Color2", ballColors[2]);
|
||||
|
||||
TELE.addData("Shoot State", shootState);
|
||||
|
||||
switch (mode) {
|
||||
|
||||
case RAPID:
|
||||
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Open
|
||||
);
|
||||
|
||||
switch (rapidMode) {
|
||||
|
||||
case INTAKE:
|
||||
|
||||
robot.setIntakePower(1);
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A2
|
||||
);
|
||||
robot.setTransferPower(-0.7);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
|
||||
setRapidMode(RapidMode.TRANSFER_OFF);
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
|
||||
case TRANSFER_OFF:
|
||||
|
||||
if (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed()) {
|
||||
setRapidMode(RapidMode.BEFORE_PULSE_OUT);
|
||||
}
|
||||
robot.setTransferPower(-0.3);
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
if (Shooter.manualFlywheel) {
|
||||
robot.setTransferPower(NewShooterTest.transferPower);
|
||||
} else {
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SHOOT:
|
||||
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_in
|
||||
);
|
||||
if (stateTime() >= 400) {
|
||||
setRapidMode(RapidMode.INTAKE);
|
||||
}
|
||||
|
||||
if (Shooter.manualFlywheel) {
|
||||
robot.setTransferPower(NewShooterTest.transferPower);
|
||||
} else {
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case SORTED:
|
||||
|
||||
switch (sortedIntakeStates) {
|
||||
case NOTHING:
|
||||
break;
|
||||
case IDLE:
|
||||
ballColors[0] = BallStates.UNKNOWN;
|
||||
ballColors[1] = BallStates.UNKNOWN;
|
||||
ballColors[2] = BallStates.UNKNOWN;
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (sortedStateTime() > 200) {
|
||||
setSortedIntakeMode(SortedIntakeStates.INTAKE_1);
|
||||
}
|
||||
break;
|
||||
case INTAKE_1:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
//TODO: ADD DELAY OR AVERGE @ DANIEL
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[0] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[0] = BallStates.PURPLE;
|
||||
}
|
||||
robot.setSpinPos(ServoPositions.spindexer_A2);
|
||||
setSortedIntakeMode(SortedIntakeStates.DELAY_1);
|
||||
}
|
||||
break;
|
||||
case DELAY_1:
|
||||
robot.setSpinPos(ServoPositions.spindexer_A2);
|
||||
if (sortedStateTime() > spinMovementTime) {
|
||||
setSortedIntakeMode(SortedIntakeStates.INTAKE_2);
|
||||
}
|
||||
break;
|
||||
case INTAKE_2:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[1] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[1] = BallStates.PURPLE;
|
||||
}
|
||||
robot.setSpinPos(ServoPositions.spindexer_A3);
|
||||
setSortedIntakeMode(SortedIntakeStates.DELAY_2);
|
||||
}
|
||||
break;
|
||||
case DELAY_2:
|
||||
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A3
|
||||
);
|
||||
|
||||
if (sortedStateTime() > spinMovementTime) {
|
||||
setSortedIntakeMode(
|
||||
SortedIntakeStates.INTAKE_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case INTAKE_3:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[2] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[2] = BallStates.PURPLE;
|
||||
}
|
||||
setSortedIntakeMode(SortedIntakeStates.REVERSE);
|
||||
|
||||
}
|
||||
break;
|
||||
case REVERSE:
|
||||
robot.setTransferPower(-0.3);
|
||||
robot.setIntakePower(-0.1);
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
case SHOOT_SORTED:
|
||||
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
|
||||
|
||||
switch (shootState) {
|
||||
case IDLE:
|
||||
shootOrder = buildShootOrder(
|
||||
ballColors,
|
||||
desiredPattern
|
||||
);
|
||||
|
||||
setShootState(SortedShootState.MOVE_TO_1);
|
||||
mode = SpindexerMode.SHOOT_SORTED;
|
||||
break;
|
||||
case MOVE_TO_1:
|
||||
|
||||
moveToSlot(shootOrder[0]);
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_1
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_1:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_1
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SHOOT_1:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_1
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_1:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Closed);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.MOVE_TO_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case MOVE_TO_2:
|
||||
|
||||
moveToSlot(shootOrder[1]);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_2
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_2:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case SHOOT_2:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_2:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Closed);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.MOVE_TO_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case MOVE_TO_3:
|
||||
|
||||
moveToSlot(shootOrder[2]);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_3
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_3:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case SHOOT_3:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_3:
|
||||
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.DONE
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case DONE:
|
||||
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setSortedIntakeMode(
|
||||
SortedIntakeStates.IDLE
|
||||
);
|
||||
|
||||
mode = SpindexerMode.SORTED;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -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);
|
||||
|
||||
}
|
||||
// 1.545
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,117 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
|
||||
@Config
|
||||
public class VelocityCommander {
|
||||
public static double xVelK = 0.05; // TODO: Tune
|
||||
public static double xAccK = 0.025; // TODO: Tune
|
||||
public static double yVelK = 0.05; // TODO: Tune
|
||||
public static double yAccK = 0.025; // TODO: Tune
|
||||
private double hoodPos = 0.88;
|
||||
private double transferPow = -1;
|
||||
private double velo = 0;
|
||||
|
||||
public VelocityCommander() {}
|
||||
|
||||
private final double veloA = -2.703087757*Math.pow(10, -14);
|
||||
private final double veloB = 2.904756341*Math.pow(10, -11);
|
||||
private final double veloC = -1.381814293*Math.pow(10, -8);
|
||||
private final double veloD = 0.000003829224585;
|
||||
private final double veloE = -0.000684090204;
|
||||
private final double veloF = 0.0822754689;
|
||||
private final double veloG = -6.743119277;
|
||||
private final double veloH = 371.7359504;
|
||||
private final double veloI = -13189.70958;
|
||||
private final double veloJ = 272005.7124;
|
||||
private final double veloK = -2474581.713;
|
||||
private double distToRPM (double dist){
|
||||
if (dist < 49) {
|
||||
velo = 2000;
|
||||
} else if (dist > 165){
|
||||
velo = 3760;
|
||||
} else {
|
||||
velo = veloA*Math.pow(dist, 10) +
|
||||
veloB*Math.pow(dist, 9) +
|
||||
veloC*Math.pow(dist, 8) +
|
||||
veloD*Math.pow(dist, 7) +
|
||||
veloE*Math.pow(dist, 6) +
|
||||
veloF*Math.pow(dist, 5) +
|
||||
veloG*Math.pow(dist, 4) +
|
||||
veloH*Math.pow(dist, 3) +
|
||||
veloI*Math.pow(dist, 2) +
|
||||
veloJ*Math.pow(dist, 1) +
|
||||
veloK;
|
||||
velo = Math.max(2000, Math.min(3760, velo));
|
||||
}
|
||||
return velo;
|
||||
}
|
||||
|
||||
private final double hoodA = -4.3276177*Math.pow(10, -13);
|
||||
private final double hoodB = 2.68062979*Math.pow(10, -10);
|
||||
private final double hoodC = -7.12859632*Math.pow(10, -8);
|
||||
private final double hoodD = 0.0000106010785;
|
||||
private final double hoodE = -0.000960693973;
|
||||
private final double hoodF = 0.0540375808;
|
||||
private final double hoodG = -1.82724027;
|
||||
private final double hoodH = 33.4797545;
|
||||
private final double hoodI = -246.888632;
|
||||
private void distToHood (double dist){
|
||||
if (dist > 112){
|
||||
hoodPos = 0.35;
|
||||
} else if (dist < 49){
|
||||
hoodPos = 0.88;
|
||||
} else {
|
||||
hoodPos = hoodA*Math.pow(dist, 8) +
|
||||
hoodB*Math.pow(dist, 7) +
|
||||
hoodC*Math.pow(dist, 6) +
|
||||
hoodD*Math.pow(dist, 5) +
|
||||
hoodE*Math.pow(dist, 4) +
|
||||
hoodF*Math.pow(dist, 3) +
|
||||
hoodG*Math.pow(dist, 2) +
|
||||
hoodH*Math.pow(dist, 1) +
|
||||
hoodI;
|
||||
|
||||
hoodPos = Math.max(0.35, Math.min(0.88, hoodPos));
|
||||
}
|
||||
}
|
||||
public double getHoodPredicted(){
|
||||
return hoodPos;
|
||||
}
|
||||
|
||||
private void distToTransferPow(double dist, double voltage){
|
||||
if (dist < 118){
|
||||
transferPow = -1;
|
||||
} else if (dist < 125){
|
||||
transferPow = -0.7;
|
||||
} else {
|
||||
transferPow = -0.5;
|
||||
}
|
||||
|
||||
// transferPow = Math.max(-0.5, Math.min(-1, transferPow * (14/voltage)));
|
||||
}
|
||||
public double getTransferPow(){return transferPow;}
|
||||
|
||||
// 27
|
||||
public double getVeloStationary (double distance){
|
||||
return distToRPM(distance);
|
||||
}
|
||||
|
||||
double predictedDist = 0;
|
||||
public void getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc, double voltage) {
|
||||
|
||||
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 goalHeight = 28;
|
||||
predictedDist = Math.sqrt(predictedDx*predictedDx + predictedDy*predictedDy + goalHeight * goalHeight);
|
||||
|
||||
distToHood(predictedDist);
|
||||
distToTransferPow(predictedDist, voltage);
|
||||
distToRPM(predictedDist);
|
||||
}
|
||||
|
||||
public double getPredictedRPM(){return velo;}
|
||||
|
||||
public double getDistance(){return predictedDist;}
|
||||
}
|
||||
@@ -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
|
||||
|
||||
Reference in New Issue
Block a user