This commit is contained in:
Zelina974 2024-02-11 16:17:58 +01:00
parent 6f7b315ea6
commit 08cdb2a091

View file

@ -14,6 +14,7 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.util.ElapsedTime; import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.IMU;
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
import com.qualcomm.robotcore.hardware.ImuOrientationOnRobot; import com.qualcomm.robotcore.hardware.ImuOrientationOnRobot;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
@ -27,108 +28,113 @@ import org.firstinspires.ftc.robotcore.external.navigation.Velocity;
@Autonomous @Autonomous
public class ftc2024_autonome extends LinearOpMode { public class ftc2024_autonome extends LinearOpMode {
private DcMotor rm; private DcMotor rm;
private DcMotor lm; private DcMotor lm;
private IMU imu; private IMU imu;
private ElapsedTime runtime = new ElapsedTime(); private ElapsedTime runtime = new ElapsedTime();
public double time_for_dist(double speed, double dist){ public double time_for_dist(double speed, double dist){
return (double) (dist/speed); return (double) (dist/speed);
} }
@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");
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();
rm.setDirection(DcMotorSimple.Direction.REVERSE); rm.setDirection(DcMotorSimple.Direction.REVERSE);
telemetry.addData("Status", "Initialized"); telemetry.addData("Status", "Initialized");
telemetry.update(); telemetry.update();
double tour_par_minute = 300.0; double tour_par_minute = 300.0;
double wheel_width = 9.0e-2; double wheel_width = 9.0e-2;
double wheel_rayon = (wheel_width)/2; double wheel_rayon = (wheel_width)/2;
double wheel_perimeter = wheel_rayon*2*Math.PI; double wheel_perimeter = wheel_rayon*2*Math.PI;
double speed = (tour_par_minute/60)*wheel_perimeter;//dist per second double speed = (tour_par_minute/60)*wheel_perimeter;//dist per second
boolean mode = true; boolean mode = true;
// Wait for the game to start (driver presses PLAY)
waitForStart(); YawPitchRollAngles robotOrientation;
robotOrientation = imu.getRobotYawPitchRollAngles();
double Yaw = robotOrientation.getYaw(AngleUnit.DEGREES);
double Pitch = robotOrientation.getPitch(AngleUnit.DEGREES);
double Roll = robotOrientation.getRoll(AngleUnit.DEGREES);
// Wait for the game to start (driver presses PLAY)
waitForStart();
runtime.reset(); runtime.reset();
if (mode){ if (mode){
//mode Elina //mode Elina
while (opModeIsActive() && (runtime.seconds() <= Yaw != 90)) { while (opModeIsActive() && Yaw <= 90.0) {
lm.setPower(1); lm.setPower(0.5);
rm.setPower(-1); rm.setPower(-0.5);
telemetry.addData("Leg 1", runtime.seconds()); Yaw = robotOrientation.getYaw(AngleUnit.DEGREES);
telemetry.update(); telemetry.addData("Leg 1", runtime.seconds());
} telemetry.update();
runtime.reset(); }
while (opModeIsActive() && (runtime.seconds() <= 121.92e-2/speed)) { runtime.reset();
lm.setPower(1); while (opModeIsActive() && (runtime.seconds() <= 121.92e-2/speed)) {
rm.setPower(1); lm.setPower(1);
telemetry.addData("Leg 2", runtime.seconds()); rm.setPower(1);
telemetry.update(); telemetry.addData("Leg 2", runtime.seconds());
} telemetry.update();
} }
else { }
double[][] operations = { else {
{-1.0,1.0}, // vectors double[][] operations = {
{1.0,1.0}, {-1.0,1.0}, // vectors
{-1.0,1.0}, {1.0,1.0},
{-1.0,-1.0}, {-1.0,1.0},
{1.0,-1.0} {-1.0,-1.0},
}; {1.0,-1.0}
//mode Aurelien };
for(int i = 0; i<operations.length; i++){ //mode Aurelien
double[] vec = operations[i]; for(int i = 0; i<operations.length; i++){
double x = vec[0]; double[] vec = operations[i];
double y = vec[1]; double x = vec[0];
double total_dist = (double) Math.sqrt(Math.pow(y,2)+Math.pow(x,2)); double y = vec[1];
double time = time_for_dist(speed, total_dist); double total_dist = (double) Math.sqrt(Math.pow(y,2)+Math.pow(x,2));
double a = (-y+x)/Math.pow(2,1/2); double time = time_for_dist(speed, total_dist);
double b = (-y-x)/Math.pow(2,1/2); double a = (-y+x)/Math.pow(2,1/2);
double vmean = (Math.abs(a)+Math.abs(b))/2; double b = (-y-x)/Math.pow(2,1/2);
double lmvalue = (a/vmean); double vmean = (Math.abs(a)+Math.abs(b))/2;
double rmvalue = (b/vmean); double lmvalue = (a/vmean);
runtime.reset(); double rmvalue = (b/vmean);
while (opModeIsActive() && (runtime.seconds() <= time)) { runtime.reset();
lm.setPower(lmvalue); while (opModeIsActive() && (runtime.seconds() <= time)) {
rm.setPower(rmvalue); lm.setPower(lmvalue);
telemetry.addData("Runtime Seconds", runtime.seconds()); rm.setPower(rmvalue);
telemetry.addData("current_operation",operations[i]); telemetry.addData("Runtime Seconds", runtime.seconds());
telemetry.addData("current_op_id",i); telemetry.addData("current_operation",operations[i]);
telemetry.addData("current_op_id",i);
telemetry.update(); telemetry.update();
} }
} }
} }
YawPitchRollAngles robotOrientation;
robotOrientation = imu.getRobotYawPitchRollAngles();
// Now use these simple methods to extract each angle // Now use these simple methods to extract each angle
// (Java type double) from the object you just created: // (Java type double) from the object you just created:
double Yaw = robotOrientation.getYaw(AngleUnit.DEGREES);
double Pitch = robotOrientation.getPitch(AngleUnit.DEGREES); telemetry.addData("yaw",Yaw);
double Roll = robotOrientation.getRoll(AngleUnit.DEGREES);
telemetry.addData("yaw",Yaw);
telemetry.update(); telemetry.update();
// run until the end of the match (driver presses STOP // run until the end of the match (driver presses STOP
} }
} }