package org.firstinspires.ftc.teamcode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.Gyroscope; import com.qualcomm.robotcore.hardware.ColorSensor; import com.qualcomm.robotcore.hardware.Servo; import com.qualcomm.robotcore.hardware.DigitalChannel; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.util.ElapsedTime; 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.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; @Autonomous public class ftc2024_autonome extends LinearOpMode { private DcMotor rm; private DcMotor lm; private IMU imu; private ElapsedTime runtime = new ElapsedTime(); YawPitchRollAngles robotOrientation; public double time_for_dist(double speed, double dist){ return (double) (dist/speed); } /* * @param double angle2go => degrees */ public double runPid(double angle2go){ robotOrientation = imu.getRobotYawPitchRollAngles(); angle2go = (angle2go*180)/Math.PI; double P = 0.5; while (opModeIsActive()){ yaw = robotOrientation.getYaw(AngleUnit.RADIANS); double currentPos = yaw; double error = yaw-currentpos; double command = (P * error)/Math.PI; command = clamp(command,.6); lm.setPower(command); rm.setPower(-command); } } double clamp(double value, double max) { return Math.max(-max, Math.min(max, value)); } @Override public void runOpMode() { lm = hardwareMap.get(DcMotor.class, "blm"); rm = hardwareMap.get(DcMotor.class, "brm"); imu = hardwareMap.get(IMU.class, "imu"); imu.initialize( new IMU.Parameters( new RevHubOrientationOnRobot( RevHubOrientationOnRobot.LogoFacingDirection.UP, RevHubOrientationOnRobot.UsbFacingDirection.FORWARD ) ) ); imu.resetYaw(); rm.setDirection(DcMotorSimple.Direction.REVERSE); telemetry.addData("Status", "Initialized"); telemetry.update(); double tour_par_minute = 300.0; double wheel_width = 9.0e-2; double wheel_rayon = (wheel_width)/2; double wheel_perimeter = wheel_rayon*2*Math.PI; double speed = (tour_par_minute/60)*wheel_perimeter;//dist per second boolean mode = true; robotOrientation = imu.getRobotYawPitchRollAngles(); double Yaw = robotOrientation.getYaw(AngleUnit.DEGREES); double Pitch = robotOrientation.getPitch(AngleUnit.DEGREES); double Roll = robotOrientation.getRoll(AngleUnit.DEGREES); double yaw_sortie; // Wait for the game to start (driver presses PLAY) waitForStart(); runtime.reset(); if (mode){ //mode Elina while (opModeIsActive() && Yaw <= 90.0) { lm.setPower(0.5); rm.setPower(-0.5); robotOrientation = imu.getRobotYawPitchRollAngles(); Yaw = robotOrientation.getYaw(AngleUnit.DEGREES); telemetry.addData("Yaw : ", Yaw); telemetry.update(); yaw_sortie = Yaw; } telemetry.addData("yaw_sortie", yaw_sortie) runtime.reset(); while (opModeIsActive() && (runtime.seconds() <= 121.92e-2/speed)) { lm.setPower(0.1); rm.setPower(0.1); telemetry.addData("Leg 2", runtime.seconds()); telemetry.update(); } } else{ while(opModeIsActive()){ Yaw = robotOrientation.getYaw(AngleUnit.DEGREES); if(Math.abs(Yaw-90.0)<=0.01){ break; } else if((Yaw - 90.0) <0){ lm.setPower((Math.abs(Yaw-90.0)/90)*0.5); rm.setPower(-(Math.abs(Yaw-90.0)/90)*0.5); } else{ rm.setPower((Math.abs(Yaw-90.0)/90)*0.5); lm.setPower(-(Math.abs(Yaw-90.0)/90)*0.5); } } } if(false){ double[][] operations = { {-1.0,1.0}, // vectors {1.0,1.0}, {-1.0,1.0}, {-1.0,-1.0}, {1.0,-1.0} }; //mode Aurelien for(int i = 0; i