ftc2024-robotcode/ftc_new.java

373 lines
14 KiB
Java
Raw Normal View History

2024-03-31 15:33:16 +02:00
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
import com.qualcomm.robotcore.robot.Robot;
import org.firstinspires.ftc.robotcore.external.Telemetry;
import com.qualcomm.robotcore.hardware.Gamepad;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.robot.Robot;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.IMU;
import com.qualcomm.robotcore.hardware.ImuOrientationOnRobot;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
import org.firstinspires.ftc.robotcore.external.navigation.Position;
import org.firstinspires.ftc.robotcore.external.navigation.Velocity;
2024-04-01 16:19:25 +02:00
@TeleOp(name = "WeRobot: FTC2024 NEW!!! Carlike", group = "WeRobot")
2024-04-01 15:54:55 +02:00
public class WEROBOT_FTC2024_New_carlike extends LinearOpMode {
2024-04-01 17:24:07 +02:00
public enum RobotMode {
ESSAIFRANCK, ELINA, NORMAL, TANK;
2024-04-01 16:54:30 +02:00
}
2024-03-31 15:33:16 +02:00
private DcMotor rm;
private DcMotor lm;
private DcMotor moissoneuse;
private DcMotorEx lmelevator;
private DcMotorEx rmelevator;
private DcMotorEx box;
private DcMotorEx rotation;
2024-04-01 17:24:07 +02:00
private ElapsedTime runtime = new ElapsedTime();
2024-04-01 17:10:52 +02:00
private RobotMode mode = RobotMode.ESSAIFRANCK;
2024-04-01 17:24:07 +02:00
/*
* La fonction pour faire des exponentielles spécifiques
*
2024-03-31 15:33:16 +02:00
* @param double t => le nombre dont on veut faire l'exponentielle
2024-04-01 17:24:07 +02:00
*
* @return double une_exponentielle_très_spéciale_de_t
*/
2024-03-31 15:33:16 +02:00
private double helloexp(double t) {
2024-04-01 17:10:52 +02:00
return (Math.exp(5 * t) - 1) / (Math.exp(5) - 1);
2024-03-31 15:33:16 +02:00
}
2024-04-01 17:24:07 +02:00
public void nextMode() {
RobotMode toNextMode;
switch (this.mode) {
case ESSAIFRANCK:
toNextMode = RobotMode.ELINA;
break;
case ELINA:
toNextMode = RobotMode.NORMAL;
break;
case NORMAL:
toNextMode = RobotMode.TANK;
break;
default:
toNextMode = RobotMode.ESSAIFRANCK;
break;
}
this.mode = toNextMode;
}
// La fonction du thread principal
2024-03-31 15:33:16 +02:00
@Override
public void runOpMode() throws InterruptedException {
2024-04-01 17:24:07 +02:00
double boxRot = 0;
2024-04-01 17:10:52 +02:00
int signeBR;
2024-04-01 17:24:07 +02:00
2024-04-01 17:10:52 +02:00
float x;
double y;
double t;
double t2;
double t3;
boolean already_b = false;
boolean already_a = false;
boolean already_x = false;
boolean already_y = false;
boolean already_up = false;
boolean already_down = false;
boolean already_ps = false;
2024-04-01 17:24:07 +02:00
2024-04-01 17:10:52 +02:00
boolean sinking = false;
boolean manualMode = false;
boolean firstLaunch = true;
telemetry.addData("Status", "Initialized");
lm = hardwareMap.get(DcMotor.class, "blm");
rm = hardwareMap.get(DcMotor.class, "brm");
rm.setDirection(DcMotor.Direction.REVERSE);
moissoneuse = hardwareMap.get(DcMotor.class, "moissonneuse");
moissoneuse.setDirection(DcMotor.Direction.REVERSE);
lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv");
lmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rmelevator = hardwareMap.get(DcMotorEx.class, "rtrselv");
rmelevator.setDirection(DcMotor.Direction.REVERSE);
rmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rotation = hardwareMap.get(DcMotorEx.class, "elvRot");
rotation.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rotation.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
box = hardwareMap.get(DcMotorEx.class, "boxRot");
box.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// box.setPositionPIDFCoefficients(5.0);
// rotation positions: 20° pos initiale par rapport au sol
// while (runtime.seconds()<0.5){
2024-04-01 17:24:07 +02:00
// rotation.setPower(0.5);
2024-04-01 17:10:52 +02:00
// }
telemetry.addData("Mode", "waiting for start");
// rotation.setVelocity(1700);
// rotation.setTargetPosition(-1000);
// rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
telemetry.addData("rotation target Pos", rotation.getTargetPosition());
telemetry.addData("rotation Pos", rotation.getCurrentPosition());
telemetry.update();
waitForStart();
rotation.setVelocity(200);
rotation.setTargetPosition(0);
rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
while (opModeIsActive()) {
2024-04-01 17:24:07 +02:00
2024-04-01 17:10:52 +02:00
x = gamepad1.left_stick_x;
y = gamepad1.left_stick_y;
2024-04-01 17:24:07 +02:00
/* définition de {@link t} sur la valeur du trigger droit du gamepad 1 */
2024-04-01 17:10:52 +02:00
t = gamepad1.right_trigger;
2024-04-01 17:24:07 +02:00
/*
* définition de {@link t2} par utilisation de la fonction {@link helloexp} sur
* {@link t}
*/
2024-04-01 17:10:52 +02:00
t2 = helloexp(t);
2024-04-01 17:24:07 +02:00
/*
* définition de {@link t3} par utilisation de la fonction {@link helloexp} sur
2024-04-01 17:10:52 +02:00
* la norme du vecteur du joystick gauche du gamepad 1 (racine carrée de {@link
2024-04-01 17:24:07 +02:00
* x} au carré plus {@link y} au carré
*/
2024-04-01 17:10:52 +02:00
t3 = helloexp(Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)));
2024-04-01 17:24:07 +02:00
telemetry.addData("Status", "Running");
if (0.1 < gamepad1.right_stick_x) {
2024-04-01 18:00:59 +02:00
boxRot = 0.1;
2024-04-01 17:24:07 +02:00
} else if (-0.1 > gamepad1.right_stick_x) {
2024-04-01 18:00:59 +02:00
boxRot = -0.1;
} else {
boxRot = 0;
2024-04-01 17:10:52 +02:00
}
2024-04-01 17:24:07 +02:00
if (gamepad1.right_trigger > 0) {
2024-04-01 17:10:52 +02:00
box.setPower(boxRot);
}
// if (boxRot <= 0){
2024-04-01 17:24:07 +02:00
// signeBR = -1;
// }
// else{
// signeBR=1;
// }
2024-04-01 17:10:52 +02:00
// if (Math.abs(boxRot) < 0.1){
2024-04-01 17:24:07 +02:00
// boxRot = 0.4*signeBR;
2024-04-01 17:10:52 +02:00
// }
// else {
2024-04-01 17:24:07 +02:00
// boxRot = 0.4*signeBR + boxRot/1.67;
// if (boxRot*signeBR > 0.9){
// boxRot = signeBR;
2024-04-01 17:10:52 +02:00
// }
2024-04-01 17:24:07 +02:00
// }
if (gamepad1.a && !already_a) {
2024-04-01 17:10:52 +02:00
nextMode();
already_a = true;
}
if (!gamepad1.a && already_a) {
already_a = false;
}
double lpower = 0.0;
double rpower = 0.0;
switch (mode) {
case NORMAL:
2024-04-01 17:24:07 +02:00
double ysign = Math.signum(y);
double xsign = Math.signum(x);
2024-04-01 17:10:52 +02:00
lpower = -ysign * t + (xsign - 2 * x) * t;
rpower = ysign * t + (xsign - 2 * x) * t;
break;
2024-04-01 17:24:07 +02:00
2024-04-01 17:10:52 +02:00
case TANK:
lpower = -y;
2024-04-01 18:00:59 +02:00
rpower = -gamepad1.right_stick_y;
2024-04-01 17:10:52 +02:00
break;
2024-04-01 17:24:07 +02:00
case ESSAIFRANCK:
2024-04-01 17:10:52 +02:00
double a = (-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;
lpower = (a / vmean) * t2;
rpower = (b / vmean) * t2;
break;
2024-04-01 17:24:07 +02:00
case ELINA:
a = (-y + x) / Math.pow(2, 1 / 2);
b = (-y - x) / Math.pow(2, 1 / 2);
2024-04-01 18:00:59 +02:00
vmean = (Math.abs(a) + Math.abs(b)) / 2;
2024-04-01 17:10:52 +02:00
lpower = (a / vmean) * t3;
rpower = (b / vmean) * t3;
break;
}
2024-04-01 17:24:07 +02:00
if (gamepad1.left_trigger > 0.1) {
2024-04-01 17:10:52 +02:00
lpower /= 3;
rpower /= 3;
}
2024-04-01 18:00:59 +02:00
lm.setPower(lpower/1.5);
rm.setPower(rpower/1.5);
2024-04-01 17:10:52 +02:00
// activation moissonneuse
if (gamepad1.b && !already_b) {
double moissoneuseSpeed = 1.0;
2024-04-01 17:24:07 +02:00
if (gamepad1.right_bumper) {
2024-04-01 17:10:52 +02:00
moissoneuseSpeed = -1.0;
}
already_b = !already_b;
if (moissoneuse.getPower() == moissoneuseSpeed) {
moissoneuse.setPower(0);
} else {
moissoneuse.setPower(moissoneuseSpeed);
}
}
if (!gamepad1.b && already_b) {
already_b = false;
}
2024-04-01 17:24:07 +02:00
// activation elevateur
if (sinking && Math.abs(lmelevator.getCurrentPosition() - 90) <= 5
&& Math.abs(rmelevator.getCurrentPosition() - 90) <= 5) {
2024-04-01 17:10:52 +02:00
lmelevator.setVelocity(100);
rmelevator.setVelocity(100);
lmelevator.setTargetPosition(0);
rmelevator.setTargetPosition(0);
lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
2024-04-01 17:24:07 +02:00
if ((gamepad1.dpad_up && !already_up) ^ (gamepad1.dpad_down && !already_down)) {
2024-04-01 17:10:52 +02:00
lmelevator.setVelocity(600);
rmelevator.setVelocity(600);
2024-04-01 17:24:07 +02:00
Long targetPosLong = (Long) Math.round(288 * 3.4);
2024-04-01 17:10:52 +02:00
int targetPos = targetPosLong.intValue();
2024-04-01 17:24:07 +02:00
if (gamepad1.dpad_down) {
2024-04-01 17:10:52 +02:00
targetPos = 90;
already_down = true;
sinking = true;
2024-04-01 17:24:07 +02:00
} else {
2024-04-01 17:10:52 +02:00
already_up = true;
sinking = false;
}
lmelevator.setTargetPosition(targetPos);
2024-04-01 17:24:07 +02:00
rmelevator.setTargetPosition(targetPos);
2024-04-01 17:10:52 +02:00
lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
2024-04-01 17:24:07 +02:00
} else if (!gamepad1.dpad_up && already_up) {
2024-04-01 17:10:52 +02:00
already_up = false;
2024-04-01 17:24:07 +02:00
} else if (!gamepad1.dpad_down && already_down) {
2024-04-01 17:10:52 +02:00
already_down = false;
}
2024-04-01 17:24:07 +02:00
if (gamepad1.ps && !already_ps) {
2024-04-01 17:10:52 +02:00
manualMode = !manualMode;
already_ps = true;
2024-04-01 17:24:07 +02:00
} else if (!gamepad1.ps && already_ps) {
2024-04-01 17:10:52 +02:00
already_ps = false;
2024-04-01 17:24:07 +02:00
}
2024-04-01 17:10:52 +02:00
// activation rotation
2024-04-01 17:24:07 +02:00
if (manualMode) {
gamepad1.setLedColor(255, 0, 0, 10);
2024-04-01 17:10:52 +02:00
lmelevator.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
rmelevator.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
rotation.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
2024-04-01 17:24:07 +02:00
if (gamepad1.dpad_up) {
2024-04-01 17:10:52 +02:00
rmelevator.setPower(0.3);
lmelevator.setPower(0.3);
2024-04-01 17:24:07 +02:00
} else if (gamepad1.dpad_down) {
2024-04-01 17:10:52 +02:00
lmelevator.setPower(-0.3);
rmelevator.setPower(-0.3);
2024-04-01 17:24:07 +02:00
} else if (gamepad1.y) {
2024-04-01 17:10:52 +02:00
double power = -0.3;
2024-04-01 17:24:07 +02:00
if (gamepad1.right_bumper) {
2024-04-01 17:10:52 +02:00
power = -power;
}
rotation.setPower(power);
2024-04-01 17:24:07 +02:00
} else {
2024-04-01 17:10:52 +02:00
lmelevator.setPower(0);
rmelevator.setPower(0);
2024-04-01 18:00:59 +02:00
rotation.setPower(0);
2024-04-01 17:10:52 +02:00
lmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rotation.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
}
2024-04-01 17:24:07 +02:00
} else {
gamepad1.setLedColor(0, 0, 255, 10);
2024-04-01 17:10:52 +02:00
}
if (!gamepad1.y && already_y && !manualMode) {
already_y = false;
}
2024-04-01 17:24:07 +02:00
if (gamepad1.y && !already_y && !manualMode) {
2024-04-01 17:10:52 +02:00
already_y = true;
int pos = rotation.getCurrentPosition();
rotation.setVelocity(200);
2024-04-01 17:24:07 +02:00
if (gamepad1.right_bumper) {
2024-04-01 17:10:52 +02:00
// rotation.setTargetPosition(pos - 25);
2024-04-01 17:24:07 +02:00
rotation.setTargetPosition(-100); // vertical si pos origine = 0
} else if (gamepad1.left_bumper) {
2024-04-01 17:10:52 +02:00
// rotation.setTargetPosition(pos + 25);
2024-04-01 17:24:07 +02:00
rotation.setTargetPosition(1000); // position basse
2024-04-01 17:10:52 +02:00
} else {
rotation.setTargetPosition(0);
}
rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
2024-04-01 17:24:07 +02:00
if (gamepad1.right_bumper && gamepad1.left_bumper) {
2024-04-01 17:10:52 +02:00
// launch the plane
}
telemetry.addData("x", x);
telemetry.addData("y", y);
telemetry.addData("mode", mode);
telemetry.addData("lpow", lpower);
telemetry.addData("rpow", rpower);
telemetry.addData("ltrigg", t);
telemetry.addData("t2", t2);
2024-04-01 17:24:07 +02:00
telemetry.addData("rotation power", boxRot);
2024-04-01 17:10:52 +02:00
telemetry.addData("mode manuel", manualMode);
telemetry.addData("Position elevateur l", lmelevator.getCurrentPosition());
telemetry.addData("Position elevateur r", rmelevator.getCurrentPosition());
2024-04-01 17:24:07 +02:00
telemetry.addData("Position rotation", rotation.getCurrentPosition());
telemetry.addData("Position box", box.getCurrentPosition());
telemetry.addData("box velocity", rotation.getVelocity());
2024-04-01 17:10:52 +02:00
telemetry.update();
}
2024-03-31 15:33:16 +02:00
}
2024-04-01 17:24:07 +02:00
2024-04-01 16:54:30 +02:00
}