helloworld XD (when someone who is not Zelina make a commit...)

This commit is contained in:
Zelina974 2024-04-06 14:17:08 +02:00
parent 95cb879f7b
commit eff1e655fe
4 changed files with 125 additions and 107 deletions

View file

@ -65,32 +65,19 @@ public class FTC2024WeRobotControl {
* to 1 * to 1
*/ */
public void boxElv(){
Parent.lmelevator.setVelocity(600);
Parent.rmelevator.setVelocity(600);
Parent.rotation.setVelocity(600);
Parent.lmelevator.setTargetPosition(50);
Parent.rmelevator.setTargetPosition(50);
Parent.rotation.setTargetPosition(30);
Parent.lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
public void boxElv() { public void boxElv() {
Parent.lmelevator.setVelocity(600); Parent.lmelevator.setVelocity(600);
Parent.rmelevator.setVelocity(600); Parent.rmelevator.setVelocity(600);
Parent.lmelevator.setTargetPosition(90); Parent.lmelevator.setTargetPosition(90);
Parent.rmelevator.setTargetPosition(90); Parent.rmelevator.setTargetPosition(90);
Parent.rotation.setVelocity(600); Parent.rotation.setVelocity(600);
Parent.rotation.setTargetPosition(-50); Parent.rotation.setTargetPosition(20);
Parent.lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION); Parent.lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION); Parent.rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION); Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
} }
public void posBasse() {
public void posBasse(){
Parent.lmelevator.setVelocity(600); Parent.lmelevator.setVelocity(600);
Parent.rmelevator.setVelocity(600); Parent.rmelevator.setVelocity(600);
Parent.rotation.setVelocity(600); Parent.rotation.setVelocity(600);
@ -115,7 +102,6 @@ public class FTC2024WeRobotControl {
return speed; return speed;
} }
/* /*
* return the needed time for a distance * return the needed time for a distance
* *
@ -139,7 +125,7 @@ public class FTC2024WeRobotControl {
* to 1 * to 1
*/ */
public void forward(double n_tiles, double motor_speed) { public void forward(double n_tiles, double motor_speed) {
double total_time = time_for_dist(n_tiles * ground_tiles_width, motor_speed); double total_time = time_for_dist(n_tiles * ground_tiles_width, Math.abs(motor_speed));
timer.reset(); timer.reset();
while (Parent.opModeIsActive() && timer.seconds() < total_time) { while (Parent.opModeIsActive() && timer.seconds() < total_time) {
Parent.lm.setPower(motor_speed); Parent.lm.setPower(motor_speed);

View file

@ -1,7 +1,18 @@
package org.firstinspires.ftc.teamcode;
import org.firstinspires.ftc.teamcode.Ftc2024_autonome_api;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
package org.firstinspires.ftc.teamcode; @Autonomous
import org.firstinspires.ftc.teamcode.Ftc2024_autonome_api; public class ftc2024_auto_r2d extends LinearOpMode{
public class ftc2024_auto_r2d extends Ftc2024_autonome_api{ //hi
public AutoMode autonomous_mode = AutoMode.R2D; public Ftc2024_autonome_api.AutoMode autonomous_mode = Ftc2024_autonome_api.AutoMode.R2D;
@Override
public void runOpMode() {
Ftc2024_autonome_api a = new Ftc2024_autonome_api();
a.hardwareMap = this.hardwareMap;
a.runOpMode();
} }
}

View file

@ -19,28 +19,29 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime; import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcode.hardware.HardwareMap;
@Autonomous @Autonomous
public class Ftc2024_autonome_api extends LinearOpMode { public class Ftc2024_autonome_api{
public enum AutoMode{ public enum AutoMode {
B2D,B4D,B2N,B4N,R2D,R4D,R2N,R4N B2D, B4D, B2N, B4N, R2D, R4D, R2N, R4N
} }
public HardwareMap hardwareMap;
public AutoMode autonomous_mode; public AutoMode autonomous_mode;
public DcMotor lm; public DcMotorEx lm;
public DcMotor rm; public DcMotorEx rm;
public DcMotorEx lmelevator; public DcMotorEx lmelevator;
public DcMotorEx rmelevator; public DcMotorEx rmelevator;
public DcMotor harvestmotor; public DcMotor harvestmotor;
public IMU imu; public IMU imu;
public DcMotorEx rotation; public DcMotorEx rotation;
@Override
public void runOpMode() { public void runOpMode() {
boolean auto = false; boolean auto = false;
lm = hardwareMap.get(DcMotor.class, "blm"); lm = hardwareMap.get(DcMotorEx.class, "blm");
rm = hardwareMap.get(DcMotor.class, "brm"); rm = hardwareMap.get(DcMotorEx.class, "brm");
harvestmotor = hardwareMap.get(DcMotor.class, "moissonneuse"); harvestmotor = hardwareMap.get(DcMotor.class, "moissonneuse");
rotation = hardwareMap.get(DcMotorEx.class, "elvRot"); rotation = hardwareMap.get(DcMotorEx.class, "elvRot");
lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv"); lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv");
@ -63,25 +64,24 @@ public class Ftc2024_autonome_api extends LinearOpMode {
imu.resetYaw(); imu.resetYaw();
YawPitchRollAngles robotOrientation; YawPitchRollAngles robotOrientation;
FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this); FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this);
autonomous_mode = AutoMode.B4D;
telemetry.addData("wait for start", ""); telemetry.addData("wait for start", "");
telemetry.update(); telemetry.update();
while (opModeInInit()){
imu.resetYaw();
waitForStart(); telemetry.addData("wait", "for start");
telemetry.addData("started", ""); telemetry.addData("Yaw", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
telemetry.update(); telemetry.update();
robotOrientation = imu.getRobotYawPitchRollAngles(); }
while (opModeIsActive()) { while (opModeIsActive()) {
if (gamepad1.a && !auto){ if (gamepad1.a && !auto) {
auto = true; auto = true;
break; break;
} }
} }
if (opModeIsActive()){ if (opModeIsActive()) {
/* /*
* autonomous_mode differents possibles values respect the next scheme: * autonomous_mode differents possibles values respect the next scheme:
* team_color_shortcode + start_line_index + direct_or_no * team_color_shortcode + start_line_index + direct_or_no
@ -103,6 +103,10 @@ public class Ftc2024_autonome_api extends LinearOpMode {
robot.harvest(0); robot.harvest(0);
robot.rotate((-90)); robot.rotate((-90));
robot.posBasse(); robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
robot.forward(3.5); robot.forward(3.5);
robot.harvest(-1); robot.harvest(-1);
robot.backward(0.5); robot.backward(0.5);
@ -110,7 +114,14 @@ public class Ftc2024_autonome_api extends LinearOpMode {
robot.forward(0.5); robot.forward(0.5);
break; break;
case B2D: case B2D:
imu.resetYaw();
robot.posBasse(); robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.addData("Yaw", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
telemetry.update();
}
robot.harvest(1); robot.harvest(1);
robot.forward(0.5); robot.forward(0.5);
robot.harvest(0); robot.harvest(0);
@ -127,6 +138,10 @@ public class Ftc2024_autonome_api extends LinearOpMode {
robot.harvest(0); robot.harvest(0);
robot.rotate(90); robot.rotate(90);
robot.posBasse(); robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
robot.forward(3.5); robot.forward(3.5);
robot.harvest(-1); robot.harvest(-1);
robot.backward(0.5); robot.backward(0.5);
@ -135,16 +150,21 @@ public class Ftc2024_autonome_api extends LinearOpMode {
break; break;
case R2D: case R2D:
robot.boxElv(); robot.boxElv();
robot.harvest(1); //rebuild
robot.forward(0.5); //robot.harvest(1);
robot.harvest(0); robot.forward(1.5);
//robot.harvest(0);
robot.rotate(90); robot.rotate(90);
robot.posBasse(); robot.posBasse();
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
telemetry.addData("pos", rotation.getCurrentPosition());
telemetry.update();
}
robot.forward(1.5); robot.forward(1.5);
robot.harvest(-1); //robot.harvest(-1);
robot.backward(0.5); //robot.backward(0.5);
robot.harvest(0); //robot.harvest(0);
robot.forward(0.5); //robot.forward(0.5);
break; break;
case B4N: case B4N:
robot.boxElv(); robot.boxElv();

View file

@ -181,6 +181,7 @@ public class WEROBOT_FTC2024_New_carlike extends LinearOpMode {
t3 = helloexp(Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2))); t3 = helloexp(Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)));
telemetry.addData("Status", "Running"); telemetry.addData("Status", "Running");
telemetry.addData("mode", mode);
if (gamepad1.right_bumper && gamepad1.left_bumper){ if (gamepad1.right_bumper && gamepad1.left_bumper){
@ -556,7 +557,7 @@ public class WEROBOT_FTC2024_New_carlike extends LinearOpMode {
//telemetry.addData("Position rotation", rotation.getCurrentPosition()); //telemetry.addData("Position rotation", rotation.getCurrentPosition());
//telemetry.addData("Position box", box.getCurrentPosition()); //telemetry.addData("Position box", box.getCurrentPosition());
//telemetry.addData("box velocity", rotation.getVelocity()); //telemetry.addData("box velocity", rotation.getVelocity());
//telemetry.update(); telemetry.update();
} }
} }