This commit is contained in:
Zelina974 2024-03-17 17:09:53 +01:00
parent 46207eda56
commit 58bd108a35

View file

@ -278,8 +278,10 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
}else{ }else{
already_up = true; already_up = true;
} }
panier1.setTargetPosition(targetPos); lmelevator.setTargetPosition(targetPos);
panier2.setTargetPosition(targetPos); rmelevator.setTargetPosition(targetPos);
lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}else if (!gamepad1.dpad_up && already_up){ }else if (!gamepad1.dpad_up && already_up){
already_up = false; already_up = false;
}else if (!gamepad1.dpad_down && already_down){ }else if (!gamepad1.dpad_down && already_down){
@ -295,7 +297,6 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
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);
// Create an object to receive the IMU angles // Create an object to receive the IMU angles
YawPitchRollAngles robotOrientation; YawPitchRollAngles robotOrientation;
robotOrientation = imu.getRobotYawPitchRollAngles(); robotOrientation = imu.getRobotYawPitchRollAngles();