Compare commits
10 Commits
danielv2
...
bfcecd42d3
| Author | SHA1 | Date | |
|---|---|---|---|
| bfcecd42d3 | |||
| 66e76285b2 | |||
| 7b923f31ca | |||
| d3bbbb7f2b | |||
| d5a3457be2 | |||
| 554204b6d4 | |||
| d586e3b4df | |||
| 2f5d4638ec | |||
| 1642e161c5 | |||
| 46a565c2c8 |
File diff suppressed because it is too large
Load Diff
@@ -6,8 +6,6 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
|
||||
@@ -71,4 +69,5 @@ public class PIDServoTest extends LinearOpMode {
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
@@ -73,12 +73,18 @@ public class FlywheelV2 {
|
||||
targetVelocity = commandedVelocity;
|
||||
velo = getVelo(shooter1CurPos, shooter2CurPos);
|
||||
// Flywheel PID code here
|
||||
if (targetVelocity - velo > 500) {
|
||||
if (targetVelocity - velo > 4500) {
|
||||
powPID = 1.0;
|
||||
} else if (velo - targetVelocity > 500) {
|
||||
} else if (velo - targetVelocity > 4500) {
|
||||
powPID = 0.0;
|
||||
} else {
|
||||
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
||||
|
||||
double a = 2539.07863;
|
||||
double c = 1967.6498;
|
||||
double d = -0.289647;
|
||||
double h = -1.1569;
|
||||
|
||||
double feed = Math.log((a / (targetVelocity + c)) + d) / h;
|
||||
|
||||
// --- PROPORTIONAL CORRECTION ---
|
||||
double error = targetVelocity - velo;
|
||||
@@ -88,7 +94,7 @@ public class FlywheelV2 {
|
||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
||||
|
||||
// --- FINAL MOTOR POWER ---
|
||||
powPID = feed + correction;
|
||||
powPID = feed;
|
||||
|
||||
// clamp to allowed range
|
||||
powPID = Math.max(0, Math.min(1, powPID));
|
||||
|
||||
@@ -14,7 +14,7 @@ public class Servos {
|
||||
|
||||
//PID constants
|
||||
// TODO: get PIDF constants
|
||||
public static double spinP = 3.4, spinI = 0, spinD = 0.075, spinF = 0.02;
|
||||
public static double spinP = 3.3, spinI = 0, spinD = 0.1, spinF = 0.02;
|
||||
public static double turrP = 4.0, turrI = 0.0, turrD = 0.0, turrF = 0.0;
|
||||
|
||||
public static double spin_scalar = 1.0086;
|
||||
|
||||
Reference in New Issue
Block a user