format tabulations in ftc2024-carlike.java, add imu

This commit is contained in:
GZod01 2024-01-07 15:29:01 +01:00
parent b770f1a271
commit a89a69841e

View file

@ -14,91 +14,94 @@ import com.qualcomm.robotcore.hardware.Servo;
@TeleOp(name="WeRobot: FTC2024 Carlike", group="WeRobot") @TeleOp(name="WeRobot: FTC2024 Carlike", group="WeRobot")
public class Werobot_FTC2024_carlike extends LinearOpMode { public class Werobot_FTC2024_carlike extends LinearOpMode {
private DcMotor rm; private DcMotor rm;
private DcMotor lm; private DcMotor lm;
private double helloexp(double t){ private IntegratingGyroscope imu;
return (Math.exp(5*t)-1)/(Math.exp(5)-1); private double helloexp(double t){
} return (Math.exp(5*t)-1)/(Math.exp(5)-1);
@Override }
public void runOpMode() throws InterruptedException { @Override
float x; public void runOpMode() throws InterruptedException {
double y; float x;
double t; double y;
double t2; double t;
double t3; double t2;
String mode = "normal"; double t3;
boolean already_a = false; String mode = "normal";
telemetry.addData("Status", "Initialized"); boolean already_a = false;
telemetry.update(); telemetry.addData("Status", "Initialized");
lm = hardwareMap.get(DcMotor.class, "blm"); telemetry.update();
rm = hardwareMap.get(DcMotor.class, "brm"); lm = hardwareMap.get(DcMotor.class, "blm");
rm.setDirection(DcMotorSimple.Direction.REVERSE); rm = hardwareMap.get(DcMotor.class, "brm");
waitForStart(); imu = hardwareMap.get(IntegratingGyroscope.class, "imu");
rm.setDirection(DcMotorSimple.Direction.REVERSE);
waitForStart();
while (opModeIsActive()) { while (opModeIsActive()) {
x = gamepad1.left_stick_x; x = gamepad1.left_stick_x;
y = gamepad1.left_stick_y; y = gamepad1.left_stick_y;
t= gamepad1.right_trigger; t= gamepad1.right_trigger;
t2 = helloexp(t); t2 = helloexp(t);
t3 = helloexp(Math.sqrt(Math.pow(x,2)+Math.pow(y,2))); t3 = helloexp(Math.sqrt(Math.pow(x,2)+Math.pow(y,2)));
telemetry.addData("Status", "Running"); telemetry.addData("Status", "Running");
if(gamepad1.a && !already_a){ if(gamepad1.a && !already_a){
if(mode=="normal"){ if(mode=="normal"){
mode="tank"; mode="tank";
}else if(mode=="tank"){ }else if(mode=="tank"){
mode = "essaifranck"; mode = "essaifranck";
}else if (mode == "essaifranck"){ }else if (mode == "essaifranck"){
mode = "elina"; mode = "elina";
}else{ }else{
mode="normal"; mode="normal";
} }
already_a = true; already_a = true;
} }
if(!gamepad1.a && already_a){ if(!gamepad1.a && already_a){
already_a = false; already_a = false;
} }
double lpower = 0.0; double lpower = 0.0;
double rpower = 0.0; double rpower = 0.0;
if(mode=="normal"){ if(mode=="normal"){
double ysign = y>0?1.0:(y<0?-1.0:0.0); double ysign = y>0?1.0:(y<0?-1.0:0.0);
double xsign = x>0?1.0:(x<0?-1.0:0.0); double xsign = x>0?1.0:(x<0?-1.0:0.0);
lpower = -ysign * t + (xsign-2*x)*t; lpower = -ysign * t + (xsign-2*x)*t;
rpower = ysign * t + (xsign-2*x)*t; rpower = ysign * t + (xsign-2*x)*t;
} }
else if (mode=="tank"){ else if (mode=="tank"){
lpower = -y; lpower = -y;
rpower = gamepad1.right_stick_y; rpower = gamepad1.right_stick_y;
} }
else if (mode=="essaifranck"){ else if (mode=="essaifranck"){
double a = (-y+x)/Math.pow(2,1/2); double a = (-y+x)/Math.pow(2,1/2);
double b = (-y-x)/Math.pow(2,1/2); double b = (-y-x)/Math.pow(2,1/2);
double vmean = (Math.abs(a)+Math.abs(b))/2; double vmean = (Math.abs(a)+Math.abs(b))/2;
lpower = (a/vmean)*t2; lpower = (a/vmean)*t2;
rpower = (b/vmean)*t2; rpower = (b/vmean)*t2;
} }
else if (mode=="elina"){ else if (mode=="elina"){
double a = (-y+x)/Math.pow(2,1/2); double a = (-y+x)/Math.pow(2,1/2);
double b = (-y-x)/Math.pow(2,1/2); double b = (-y-x)/Math.pow(2,1/2);
double vmean = (Math.abs(a)+Math.abs(b))/2; double vmean = (Math.abs(a)+Math.abs(b))/2;
lpower = (a/vmean)*t3; lpower = (a/vmean)*t3;
rpower = (b/vmean)*t3; rpower = (b/vmean)*t3;
} }
if(!(gamepad1.left_bumper)){ if(!(gamepad1.left_bumper)){
lpower/=3; lpower/=3;
rpower/=3; rpower/=3;
} }
lm.setPower(lpower); lm.setPower(lpower);
rm.setPower(rpower); rm.setPower(rpower);
telemetry.addData("x",x); telemetry.addData("x",x);
telemetry.addData("y",y); telemetry.addData("y",y);
telemetry.addData("lpow",lpower); telemetry.addData("lpow",lpower);
telemetry.addData("rpow",rpower); telemetry.addData("rpow",rpower);
telemetry.addData("ltrigg",t); telemetry.addData("ltrigg",t);
telemetry.addData("t2",t2); telemetry.addData("t2",t2);
telemetry.addData("mode",mode); telemetry.addData("mode",mode);
telemetry.update(); telemetry.addData("imu angular orientation", imu.getAngularOrientation());
} telemetry.update();
} }
}
} }