loop times at 30ms
This commit is contained in:
@@ -821,7 +821,7 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
startAuto();
|
startAuto();
|
||||||
|
|
||||||
if (stack3){
|
if (stack3){
|
||||||
cycleStackFar();
|
//cycleStackFar();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gatePickup || stack3){
|
if (gatePickup || stack3){
|
||||||
@@ -878,61 +878,61 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
Actions.runBlocking(leaveFromShoot.build());
|
Actions.runBlocking(leaveFromShoot.build());
|
||||||
}
|
}
|
||||||
|
|
||||||
void cycleStackFar(){
|
// void cycleStackFar(){
|
||||||
Actions.runBlocking(
|
// Actions.runBlocking(
|
||||||
new ParallelAction(
|
// new ParallelAction(
|
||||||
pickup3.build(),
|
// pickup3.build(),
|
||||||
manageShooterAuto(
|
// manageShooterAuto(
|
||||||
intake3Time,
|
// intake3Time,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501
|
// 0.501
|
||||||
),
|
// ),
|
||||||
intake(intake3Time),
|
// intake(intake3Time),
|
||||||
detectObelisk(
|
// detectObelisk(
|
||||||
intake3Time,
|
// intake3Time,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
obeliskTurrPos3
|
// obeliskTurrPos3
|
||||||
)
|
// )
|
||||||
|
//
|
||||||
)
|
// )
|
||||||
);
|
// );
|
||||||
|
//
|
||||||
motif = turret.getObeliskID();
|
// motif = turret.getObeliskID();
|
||||||
|
//
|
||||||
if (motif == 0) motif = prevMotif;
|
// if (motif == 0) motif = prevMotif;
|
||||||
prevMotif = motif;
|
// prevMotif = motif;
|
||||||
|
//
|
||||||
Actions.runBlocking(
|
// Actions.runBlocking(
|
||||||
new ParallelAction(
|
// new ParallelAction(
|
||||||
manageFlywheelAuto(
|
// manageFlywheelAuto(
|
||||||
shoot3Time,
|
// shoot3Time,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501
|
// 0.501
|
||||||
),
|
// ),
|
||||||
shoot3.build(),
|
// shoot3.build(),
|
||||||
prepareShootAll(colorSenseTime, shoot3Time, motif)
|
// prepareShootAll(colorSenseTime, shoot3Time, motif)
|
||||||
)
|
// )
|
||||||
);
|
// );
|
||||||
|
//
|
||||||
Actions.runBlocking(
|
// Actions.runBlocking(
|
||||||
new ParallelAction(
|
// new ParallelAction(
|
||||||
manageShooterAuto(
|
// manageShooterAuto(
|
||||||
finalShootAllTime,
|
// finalShootAllTime,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501,
|
// 0.501,
|
||||||
0.501
|
// 0.501
|
||||||
),
|
// ),
|
||||||
shootAllAuto(finalShootAllTime, finalSpindexerSpeedIncrease)
|
// shootAllAuto(finalShootAllTime, finalSpindexerSpeedIncrease)
|
||||||
)
|
// )
|
||||||
|
//
|
||||||
);
|
// );
|
||||||
}
|
// }
|
||||||
}
|
}
|
||||||
@@ -118,6 +118,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
servo.setTransferPos(transferServo_out);
|
servo.setTransferPos(transferServo_out);
|
||||||
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
@@ -141,8 +142,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
|
||||||
|
|
||||||
//TURRET TRACKING
|
//TURRET TRACKING
|
||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
double robX = drive.localizer.getPose().position.x;
|
||||||
|
|||||||
@@ -38,6 +38,8 @@ public class Flywheel {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Set the robot PIDF for the next cycle.
|
// Set the robot PIDF for the next cycle.
|
||||||
|
private double prevF = 0.501;
|
||||||
|
public static int voltagePIDFDifference = 5;
|
||||||
public void setPIDF(double p, double i, double d, double f) {
|
public void setPIDF(double p, double i, double d, double f) {
|
||||||
shooterPIDF1.p = p;
|
shooterPIDF1.p = p;
|
||||||
shooterPIDF1.i = i;
|
shooterPIDF1.i = i;
|
||||||
@@ -47,6 +49,10 @@ public class Flywheel {
|
|||||||
shooterPIDF2.i = i;
|
shooterPIDF2.i = i;
|
||||||
shooterPIDF2.d = d;
|
shooterPIDF2.d = d;
|
||||||
shooterPIDF2.f = f;
|
shooterPIDF2.f = f;
|
||||||
|
if (Math.abs(prevF - f) > voltagePIDFDifference){
|
||||||
|
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||||
|
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert from RPM to Ticks per Second
|
// Convert from RPM to Ticks per Second
|
||||||
|
|||||||
Reference in New Issue
Block a user