ftc2024-robotcode/ftc2024_autonome_api.java

247 lines
9.6 KiB
Java
Raw Normal View History

package org.firstinspires.ftc.teamcode;
//import FTC2024WeRobotControl; //a tester car pas sur que ça fonctionne
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.IMU;
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
import com.qualcomm.robotcore.hardware.ImuOrientationOnRobot;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcode.hardware.HardwareMap;
@Autonomous
public class Ftc2024_autonome_api{
public enum AutoMode {
B2D, B4D, B2N, B4N, R2D, R4D, R2N, R4N
2024-04-05 18:10:57 +02:00
}
public HardwareMap hardwareMap;
2024-04-05 18:10:57 +02:00
public AutoMode autonomous_mode;
public DcMotorEx lm;
public DcMotorEx rm;
public DcMotorEx lmelevator;
public DcMotorEx rmelevator;
public DcMotor harvestmotor;
public IMU imu;
public DcMotorEx rotation;
public void runOpMode() {
boolean auto = false;
lm = hardwareMap.get(DcMotorEx.class, "blm");
rm = hardwareMap.get(DcMotorEx.class, "brm");
harvestmotor = hardwareMap.get(DcMotor.class, "moissonneuse");
rotation = hardwareMap.get(DcMotorEx.class, "elvRot");
2024-04-06 10:40:00 +02:00
lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv");
2024-04-06 11:56:53 +02:00
lmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
2024-04-06 10:40:00 +02:00
rmelevator = hardwareMap.get(DcMotorEx.class, "rtrselv");
2024-04-06 11:56:53 +02:00
rmelevator.setDirection(DcMotor.Direction.REVERSE);
rmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rm.setDirection(DcMotor.Direction.REVERSE);
rotation.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
imu = hardwareMap.get(IMU.class, "imu");
imu.initialize(
new IMU.Parameters(
new RevHubOrientationOnRobot(
RevHubOrientationOnRobot.LogoFacingDirection.UP,
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)));
imu.resetYaw();
YawPitchRollAngles robotOrientation;
FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this);
telemetry.addData("wait for start", "");
telemetry.update();
while (opModeInInit()){
imu.resetYaw();
telemetry.addData("wait", "for start");
telemetry.addData("Yaw", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
telemetry.update();
}
2024-04-06 11:56:53 +02:00
while (opModeIsActive()) {
if (gamepad1.a && !auto) {
2024-04-06 11:56:53 +02:00
auto = true;
break;
}
}
if (opModeIsActive()) {
/*
* autonomous_mode differents possibles values respect the next scheme:
* team_color_shortcode + start_line_index + direct_or_no
*
* team_color_shortcode = "b" for blue & "r" for red
* start_line_index = 4 or 2 see competition manual appendix B Tile location
* plan
* direct_or_no = "d" to direct go to pixel deliver zone or "n" to harvest
* pixels before to go in deliver zone
*
* default is "b4d"
*/
switch (autonomous_mode) {
default:
robot.boxElv();
2024-04-06 11:56:53 +02:00
robot.harvest(1);
2024-04-06 10:05:34 +02:00
robot.forward(2);
2024-04-06 14:47:49 +02:00
/*robot.harvest(0);
robot.rotate((-90));
2024-04-06 11:56:53 +02:00
robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
2024-04-06 10:05:34 +02:00
robot.forward(3.5);
robot.harvest(-1);
2024-04-06 10:05:34 +02:00
robot.backward(0.5);
robot.harvest(0);
2024-04-06 14:47:49 +02:00
robot.forward(0.5);*/
break;
2024-04-05 18:10:57 +02:00
case B2D:
imu.resetYaw();
2024-04-06 11:56:53 +02:00
robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.addData("Yaw", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
telemetry.update();
}
2024-04-06 11:56:53 +02:00
robot.harvest(1);
2024-04-06 09:51:34 +02:00
robot.forward(1);
2024-04-06 14:47:49 +02:00
robot.harvest(0);
/* robot.forward(1);
2024-04-06 11:56:53 +02:00
robot.harvest(-1);
robot.backward(0.5);
robot.harvest(0);
2024-04-06 14:47:49 +02:00
robot.forward(0.5);*/
break;
2024-04-05 18:10:57 +02:00
case R4D:
robot.boxElv();
2024-04-06 11:56:53 +02:00
robot.harvest(1);
2024-04-06 10:05:34 +02:00
robot.forward(2);
2024-04-06 11:56:53 +02:00
robot.harvest(0);
robot.rotate(90);
2024-04-06 10:40:00 +02:00
robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
2024-04-06 10:05:34 +02:00
robot.forward(3.5);
robot.harvest(-1);
2024-04-06 10:05:34 +02:00
robot.backward(0.5);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
break;
2024-04-05 18:10:57 +02:00
case R2D:
robot.boxElv();
//rebuild
//robot.harvest(1);
robot.forward(1.5);
//robot.harvest(0);
robot.rotate(90);
2024-04-06 11:56:53 +02:00
robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
2024-04-06 10:10:52 +02:00
robot.forward(1.5);
//robot.harvest(-1);
//robot.backward(0.5);
//robot.harvest(0);
//robot.forward(0.5);
break;
2024-04-05 18:10:57 +02:00
case B4N:
robot.boxElv();
robot.forward(1.5);
robot.rotate(90);
robot.harvest();
robot.forward(3);
robot.harvest(0);
robot.rotate(180);
robot.forward(1);
robot.rotate(-90);
robot.forward(1);
robot.rotate(90);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
break;
2024-04-05 18:10:57 +02:00
case B2N:
robot.boxElv();
robot.forward(1.5);
robot.rotate(90);
robot.harvest();
robot.forward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
robot.rotate(180);
robot.forward(1);
robot.rotate(-90);
robot.forward(1);
robot.rotate(90);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
break;
2024-04-05 18:10:57 +02:00
case R4N:
robot.boxElv();
robot.forward(1.5);
robot.rotate(-90);
robot.harvest();
robot.forward(3);
robot.harvest(0);
robot.rotate(180);
robot.forward(1);
robot.rotate(90);
robot.forward(1);
robot.rotate(-90);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
break;
2024-04-05 18:10:57 +02:00
case R2N:
robot.boxElv();
robot.forward(1.5);
robot.rotate(-90);
robot.harvest();
robot.forward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
robot.rotate(180);
robot.forward(1);
robot.rotate(90);
robot.forward(1);
robot.rotate(-90);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-04-06 09:51:34 +02:00
robot.forward(1);
break;
}
}
}
2024-04-06 09:51:34 +02:00
}