Update ftc2024_autonome_api.java

ça fonctionne
This commit is contained in:
Zelina974 2024-03-10 17:04:53 +01:00 committed by GitHub
parent 2af007c7de
commit a426d6d40a
No known key found for this signature in database
GPG key ID: B5690EEEBB952194

View file

@ -1,6 +1,6 @@
package org.firstinspires.ftc.teamcode; package org.firstinspires.ftc.teamcode;
import fr.werobot.ftc2024.robotcontrol.FTC2024WeRobotControl; //a tester car pas sur que ça fonctionne //import FTC2024WeRobotControl; //a tester car pas sur que ça fonctionne
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
@ -21,146 +21,122 @@ import com.qualcomm.robotcore.util.ElapsedTime;
@Autonomous @Autonomous
public class ftc2024_autonome_api extends LinearOpMode { public class Ftc2024_autonome_api extends LinearOpMode {
public String autonomous_mode; public String autonomous_mode;
public DcMotor lm; public DcMotor lm;
public DcMotor rm; public DcMotor rm;
public DcMotor harvestmotor; public DcMotor harvestmotor;
public IMU imu; public IMU imu;
public YawPitchRollAngle robotOrientation;
@Override @Override
public void runOpMode() { public void runOpMode() {
lm = hardwareMap.get(DcMotor.class, "blm"); lm = hardwareMap.get(DcMotor.class, "blm");
rm = hardwareMap.get(DcMotor.class, "brm"); rm = hardwareMap.get(DcMotor.class, "brm");
harvestmotor = hardwareMap.get(DcMotor.class, "flm"); harvestmotor = hardwareMap.get(DcMotor.class, "flm");
rm.setDirection(DcMotor.Direction.REVERSE); rm.setDirection(DcMotor.Direction.REVERSE);
imu = hardwareMap.get(IMU.class, "imu"); imu = hardwareMap.get(IMU.class, "imu");
imu.initialize( imu.initialize(
new IMU.Parameters( new IMU.Parameters(
new RevHubOrientationOnRobot( new RevHubOrientationOnRobot(
RevHubOrientationOnRobot.LogoFacingDirection.UP, RevHubOrientationOnRobot.LogoFacingDirection.UP,
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD RevHubOrientationOnRobot.UsbFacingDirection.FORWARD
) )
) )
); );
imu.resetYaw(); imu.resetYaw();
// YawPitchRollAngle robotOrientation; // FTC2024WeRobotControl à besoin de robotOrientation comme variable de Parent (donc de cette classe actuelle), n'est il pas posible de définir robotOrientation dans la classe? YawPitchRollAngles robotOrientation;
FTC2024WeRobotControl robot = FTC2024WeRobotControl(this); FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this);
autonomous_mode = "b4d";
waitForStart(); telemetry.addData("wait for start","");
robotOrientation = imu.getYawPitchRollAngles(); telemetry.update();
if(opModeIsRunning()){ waitForStart();
/* telemetry.addData("started","");
* autonomous_mode differents possibles values respect the next scheme: telemetry.update();
* team_color_shortcode + start_line_index + direct_or_no robotOrientation = imu.getRobotYawPitchRollAngles();
*
* team_color_shortcode = "b" for blue & "r" for red if(opModeIsActive()){
* 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 * autonomous_mode differents possibles values respect the next scheme:
* * team_color_shortcode + start_line_index + direct_or_no
* default is "b4d" *
*/ * team_color_shortcode = "b" for blue & "r" for red
switch (autonomous_mode){ * start_line_index = 4 or 2 see competition manual appendix B Tile location plan
default: * direct_or_no = "d" to direct go to pixel deliver zone or "n" to harvest pixels before to go in deliver zone
robot.forward(0.5); *
robot.rotate((-90)); * default is "b4d"
robot.forward(1.5); */
robot.harvest(-1); switch (autonomous_mode){
robot.backward(1); case ("b4d"):
robot.harvest(0); telemetry.addData("cas b4d lancé","");
break; telemetry.update();
case ("b2d"): robot.forward(0.5);
robot.forward(0.5); robot.rotate(-90.0);
robot.rotate((-90)); robot.forward(1.5);
robot.forward(2.5); robot.harvest(-1);
robot.harvest(-1); robot.backward(1);
robot.backward(1); robot.harvest(0);
robot.harvest(0); telemetry.addData("fin de b4d","");
break; telemetry.update();
case ("r4d"): break;
robot.forward(0.5); case ("b2d"):
robot.rotate(90); telemetry.addData("cas b2d lancé","");
robot.forward(1.5); telemetry.update();
robot.harvest(-1); robot.forward(0.5);
robot.backward(1); robot.rotate(-90.0);
robot.harvest(0); robot.forward(2.5);
break; robot.harvest(-1);
case ("r2d"): robot.backward(1);
robot.forward(0.5); robot.harvest(0);
robot.rotate(90); telemetry.addData("fin de b2d","");
robot.forward(2.5); telemetry.update();
robot.harvest(-1); break;
robot.backward(1); case ("r4d"):
robot.harvest(0); telemetry.addData("cas r4d lancé","");
break; telemetry.update();
case ("b4n"): robot.forward(0.5);
robot.forward(1.5); robot.rotate(90.0);
robot.rotate(90); robot.forward(1.5);
robot.harvest(); robot.harvest(-1);
robot.forward(3); robot.backward(1);
robot.harvest(0); robot.harvest(0);
robot.rotate(180); telemetry.addData("fin de r4d","");
robot.forward(1); telemetry.update();
robot.rotate(-90); break;
robot.forward(1); case ("r2d"):
robot.rotate(90); telemetry.addData("cas r2d lancé","");
robot.forward(2.5); telemetry.update();
robot.harvest(-1); robot.forward(0.5);
robot.backward(1); robot.rotate(90.0);
robot.harvest(0); robot.forward(2.5);
break; robot.harvest(-1);
case ("b2n"): robot.backward(1);
robot.forward(1.5); robot.harvest(0);
robot.rotate(90); telemetry.addData("fin de r2d","");
robot.harvest(); telemetry.update();
robot.forward(1); break;
robot.harvest(0);
robot.rotate(180); case ("b4n"):
robot.forward(1);
robot.rotate(-90); break;
robot.forward(1); case ("b2n"):
robot.rotate(90);
robot.forward(2.5); break;
robot.harvest(-1); case ("r4n"):
robot.backward(1);
robot.harvest(0); break;
break; case ("r2n"):
case ("r4n"):
robot.forward(1.5); break;
robot.rotate(-90); default:
robot.harvest(); break;
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);
break;
case ("r2n"):
robot.forward(1.5);
robot.rotate(-90);
robot.harvest();
robot.forward(1);
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);
}
}
} }
} }