stash
This commit is contained in:
@@ -7,14 +7,6 @@ import com.qualcomm.robotcore.hardware.NormalizedColorSensor;
|
|||||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
import static org.firstinspires.ftc.teamcode.constants.Color.*;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.Light0;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.Light1;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.Light2;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.Light3;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.LightGreen;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.LightOrange;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.LightPurple;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.colorFilterAlpha;
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.shootAllSpindexerSpeedIncrease;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.shootAllSpindexerSpeedIncrease;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinEndPos;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||||
@@ -29,30 +21,36 @@ import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
|||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|
||||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
|
||||||
import java.util.Objects;
|
|
||||||
|
|
||||||
public class Spindexer {
|
public class Spindexer {
|
||||||
|
|
||||||
// Array of commandedIntakePositions with contents
|
Robot robot;
|
||||||
// {RearCenter, FrontDriver, FrontPassenger}
|
Servos servos;
|
||||||
static final int[][] RotatedBallPositions = {{0, 2, 1}, {1, 0, 2}, {2, 1, 0}};
|
Flywheel flywheel;
|
||||||
|
MecanumDrive drive;
|
||||||
|
double lastKnownSpinPos = 0.0;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
|
|
||||||
|
double spinCurrentPos = 0.0;
|
||||||
|
|
||||||
public int commandedIntakePosition = 0;
|
public int commandedIntakePosition = 0;
|
||||||
|
|
||||||
public double distanceRearCenter = 0.0;
|
public double distanceRearCenter = 0.0;
|
||||||
public double distanceFrontDriver = 0.0;
|
public double distanceFrontDriver = 0.0;
|
||||||
public double distanceFrontPassenger = 0.0;
|
public double distanceFrontPassenger = 0.0;
|
||||||
|
|
||||||
public double spindexerWiggle = 0.01;
|
public double spindexerWiggle = 0.01;
|
||||||
|
|
||||||
public double spindexerOuttakeWiggle = 0.01;
|
public double spindexerOuttakeWiggle = 0.01;
|
||||||
|
private double prevPos = 0.0;
|
||||||
public double spindexerPosOffset = 0.00;
|
public double spindexerPosOffset = 0.00;
|
||||||
public static int shootWaitMax = 4;
|
public static int shootWaitMax = 4;
|
||||||
public Types.Motif desiredMotif = Types.Motif.NONE;
|
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
||||||
// For Use
|
// For Use
|
||||||
enum RotatedBallPositionNames {
|
enum RotatedBallPositionNames {
|
||||||
REARCENTER,
|
REARCENTER,
|
||||||
@@ -87,29 +85,26 @@ public class Spindexer {
|
|||||||
|
|
||||||
int shootWaitCount = 0;
|
int shootWaitCount = 0;
|
||||||
|
|
||||||
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
|
||||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||||
public IntakeState prevIntakeState = IntakeState.UNKNOWN_START;
|
public IntakeState prevIntakeState = IntakeState.UNKNOWN_START;
|
||||||
public int unknownColorDetect = 0;
|
public int unknownColorDetect = 0;
|
||||||
public int counter = 0;
|
public enum BallColor {
|
||||||
Robot robot;
|
UNKNOWN,
|
||||||
Servos servos;
|
GREEN,
|
||||||
Flywheel flywheel;
|
PURPLE
|
||||||
MecanumDrive drive;
|
}
|
||||||
double lastKnownSpinPos = 0.0;
|
|
||||||
MultipleTelemetry TELE;
|
class BallPosition {
|
||||||
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
boolean isEmpty = true;
|
||||||
double spinCurrentPos = 0.0;
|
int foundEmpty = 0;
|
||||||
int shootWaitCount = 0;
|
BallColor ballColor = BallColor.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
BallPosition[] ballPositions = new BallPosition[3];
|
BallPosition[] ballPositions = new BallPosition[3];
|
||||||
double[] outakePositions =
|
|
||||||
{spindexer_outtakeBall1 + spindexerPosOffset,
|
public boolean init () {
|
||||||
spindexer_outtakeBall2 + spindexerPosOffset,
|
return true;
|
||||||
spindexer_outtakeBall3 + spindexerPosOffset};
|
}
|
||||||
double[] intakePositions =
|
|
||||||
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
|
||||||
private double prevPos = 0.0;
|
|
||||||
private double intakeTicker = 0;
|
|
||||||
|
|
||||||
public Spindexer(HardwareMap hardwareMap) {
|
public Spindexer(HardwareMap hardwareMap) {
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
@@ -123,11 +118,34 @@ public class Spindexer {
|
|||||||
ballPositions[1] = new BallPosition();
|
ballPositions[1] = new BallPosition();
|
||||||
ballPositions[2] = new BallPosition();
|
ballPositions[2] = new BallPosition();
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean init() {
|
|
||||||
return true;
|
double[] outakePositions =
|
||||||
}
|
{spindexer_outtakeBall1+spindexerPosOffset,
|
||||||
|
spindexer_outtakeBall2+spindexerPosOffset,
|
||||||
|
spindexer_outtakeBall3+spindexerPosOffset};
|
||||||
|
|
||||||
|
double[] intakePositions =
|
||||||
|
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
||||||
|
|
||||||
|
public int counter = 0;
|
||||||
|
|
||||||
|
// private double getTimeSeconds ()
|
||||||
|
// {
|
||||||
|
// return (double) System.currentTimeMillis()/1000.0;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public double getPos() {
|
||||||
|
// robot.spin1Pos.getVoltage();
|
||||||
|
// robot.spin1Pos.getMaxVoltage();
|
||||||
|
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public void manageSpindexer() {
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
|
||||||
public void resetBallPosition (int pos) {
|
public void resetBallPosition (int pos) {
|
||||||
ballPositions[pos].isEmpty = true;
|
ballPositions[pos].isEmpty = true;
|
||||||
@@ -246,7 +264,6 @@ public class Spindexer {
|
|||||||
|
|
||||||
return newPos1Detection;
|
return newPos1Detection;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Has code to unjam spindexer
|
// Has code to unjam spindexer
|
||||||
private void moveSpindexerToPos(double pos) {
|
private void moveSpindexerToPos(double pos) {
|
||||||
servos.setSpinPos(pos);
|
servos.setSpinPos(pos);
|
||||||
@@ -263,61 +280,12 @@ public class Spindexer {
|
|||||||
// prevPos = pos;
|
// prevPos = pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
// private double getTimeSeconds ()
|
|
||||||
// {
|
|
||||||
// return (double) System.currentTimeMillis()/1000.0;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// public double getPos() {
|
|
||||||
// robot.spin1Pos.getVoltage();
|
|
||||||
// robot.spin1Pos.getMaxVoltage();
|
|
||||||
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
|
||||||
// }
|
|
||||||
|
|
||||||
// public void manageSpindexer() {
|
|
||||||
//
|
|
||||||
// }
|
|
||||||
|
|
||||||
public void stopSpindexer() {
|
public void stopSpindexer() {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private double prevLight = 0.0;
|
private double prevLight = 0.0;
|
||||||
public void ballCounterLight(){
|
public void ballCounterLight(){
|
||||||
public double getRearCenterLight() {
|
|
||||||
BallColor color = GetRearCenterColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
public double getDriverLight() {
|
|
||||||
BallColor color = GetFrontDriverColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
public double getPassengerLight() {
|
|
||||||
BallColor color = GetFrontPassengerColor();
|
|
||||||
if (Objects.equals(color, BallColor.GREEN)) {
|
|
||||||
return LightGreen;
|
|
||||||
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
|
||||||
return LightPurple;
|
|
||||||
} else {
|
|
||||||
return LightOrange;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
public double ballCounterLight() {
|
|
||||||
int counter = 0;
|
int counter = 0;
|
||||||
if (!ballPositions[0].isEmpty){
|
if (!ballPositions[0].isEmpty){
|
||||||
counter++;
|
counter++;
|
||||||
@@ -336,16 +304,8 @@ public class Spindexer {
|
|||||||
light = Light2;
|
light = Light2;
|
||||||
} else if (counter == 1){
|
} else if (counter == 1){
|
||||||
light = Light1;
|
light = Light1;
|
||||||
|
|
||||||
if (counter == 3) {
|
|
||||||
return Light3;
|
|
||||||
} else if (counter == 2) {
|
|
||||||
return Light2;
|
|
||||||
} else if (counter == 1) {
|
|
||||||
return Light1;
|
|
||||||
} else {
|
} else {
|
||||||
light = Light0;
|
light = Light0;
|
||||||
return Light0;
|
|
||||||
}
|
}
|
||||||
if (light != prevLight){
|
if (light != prevLight){
|
||||||
robot.light.setPosition(light);
|
robot.light.setPosition(light);
|
||||||
@@ -361,6 +321,7 @@ public class Spindexer {
|
|||||||
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private double intakeTicker = 0;
|
||||||
public boolean processIntake() {
|
public boolean processIntake() {
|
||||||
|
|
||||||
switch (currentIntakeState) {
|
switch (currentIntakeState) {
|
||||||
@@ -618,18 +579,15 @@ public class Spindexer {
|
|||||||
public void prepareShootAll(){
|
public void prepareShootAll(){
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_PREP;
|
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_PREP;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void prepareShootAllContinous(){
|
public void prepareShootAllContinous(){
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_PREP_CONTINOUS;
|
currentIntakeState = Spindexer.IntakeState.SHOOT_PREP_CONTINOUS;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void shootAll () {
|
public void shootAll () {
|
||||||
ballPositions[0].isEmpty = false;
|
ballPositions[0].isEmpty = false;
|
||||||
ballPositions[1].isEmpty = false;
|
ballPositions[1].isEmpty = false;
|
||||||
ballPositions[2].isEmpty = false;
|
ballPositions[2].isEmpty = false;
|
||||||
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
currentIntakeState = Spindexer.IntakeState.SHOOTNEXT;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void shootAllContinous(){
|
public void shootAllContinous(){
|
||||||
ballPositions[0].isEmpty = false;
|
ballPositions[0].isEmpty = false;
|
||||||
ballPositions[1].isEmpty = false;
|
ballPositions[1].isEmpty = false;
|
||||||
@@ -637,7 +595,8 @@ public class Spindexer {
|
|||||||
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean shootAllComplete() {
|
public boolean shootAllComplete ()
|
||||||
|
{
|
||||||
return ((currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_PREP) &&
|
return ((currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_PREP) &&
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_READY) &&
|
(currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_READY) &&
|
||||||
(currentIntakeState != Spindexer.IntakeState.SHOOTMOVING) &&
|
(currentIntakeState != Spindexer.IntakeState.SHOOTMOVING) &&
|
||||||
@@ -651,7 +610,8 @@ public class Spindexer {
|
|||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void update() {
|
public void update()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
public BallColor GetFrontDriverColor () {
|
public BallColor GetFrontDriverColor () {
|
||||||
@@ -665,48 +625,6 @@ public class Spindexer {
|
|||||||
public BallColor GetRearCenterColor () {
|
public BallColor GetRearCenterColor () {
|
||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
||||||
}
|
}
|
||||||
|
|
||||||
// For Use
|
|
||||||
enum RotatedBallPositionNames {
|
|
||||||
REARCENTER,
|
|
||||||
FRONTDRIVER,
|
|
||||||
FRONTPASSENGER
|
|
||||||
}
|
|
||||||
|
|
||||||
enum IntakeState {
|
|
||||||
UNKNOWN_START,
|
|
||||||
UNKNOWN_MOVE,
|
|
||||||
UNKNOWN_DETECT,
|
|
||||||
INTAKE,
|
|
||||||
FINDNEXT,
|
|
||||||
MOVING,
|
|
||||||
FULL,
|
|
||||||
SHOOTNEXT,
|
|
||||||
SHOOTMOVING,
|
|
||||||
SHOOTWAIT,
|
|
||||||
SHOOT_ALL_PREP,
|
|
||||||
SHOOT_ALL_READY,
|
|
||||||
SHOOT_PREP_CONTINOUS,
|
|
||||||
SHOOT_CONTINOUS
|
|
||||||
}
|
|
||||||
|
|
||||||
public enum BallColor {
|
|
||||||
UNKNOWN,
|
|
||||||
GREEN,
|
|
||||||
PURPLE
|
|
||||||
}
|
|
||||||
|
|
||||||
class spindexerBallRoatation {
|
|
||||||
int rearCenter = 0; // aka commanded Position
|
|
||||||
int frontDriver = 0;
|
|
||||||
int frontPassenger = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
class BallPosition {
|
|
||||||
boolean isEmpty = true;
|
|
||||||
int foundEmpty = 0;
|
|
||||||
BallColor ballColor = BallColor.UNKNOWN;
|
|
||||||
}
|
|
||||||
private double prevPow = 0.501;
|
private double prevPow = 0.501;
|
||||||
public void setIntakePower(double pow){
|
public void setIntakePower(double pow){
|
||||||
if (prevPow != 0.501 && prevPow != pow){
|
if (prevPow != 0.501 && prevPow != pow){
|
||||||
|
|||||||
Reference in New Issue
Block a user