Merge branch 'master' of https://forge.gzod01.fr/werobot/ftc2024-robotcode
This commit is contained in:
commit
f87d734437
4 changed files with 125 additions and 107 deletions
|
@ -65,31 +65,18 @@ public class FTC2024WeRobotControl {
|
|||
* 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() {
|
||||
Parent.lmelevator.setVelocity(600);
|
||||
Parent.rmelevator.setVelocity(600);
|
||||
Parent.lmelevator.setTargetPosition(90);
|
||||
Parent.rmelevator.setTargetPosition(90);
|
||||
Parent.rotation.setVelocity(600);
|
||||
Parent.rotation.setTargetPosition(-50);
|
||||
Parent.rotation.setTargetPosition(20);
|
||||
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 posBasse() {
|
||||
Parent.lmelevator.setVelocity(600);
|
||||
Parent.rmelevator.setVelocity(600);
|
||||
|
@ -115,7 +102,6 @@ public class FTC2024WeRobotControl {
|
|||
return speed;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* return the needed time for a distance
|
||||
*
|
||||
|
@ -139,7 +125,7 @@ public class FTC2024WeRobotControl {
|
|||
* to 1
|
||||
*/
|
||||
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();
|
||||
while (Parent.opModeIsActive() && timer.seconds() < total_time) {
|
||||
Parent.lm.setPower(motor_speed);
|
||||
|
|
|
@ -1,7 +1,18 @@
|
|||
|
||||
package org.firstinspires.ftc.teamcode;
|
||||
import org.firstinspires.ftc.teamcode.Ftc2024_autonome_api;
|
||||
public class ftc2024_auto_r2d extends Ftc2024_autonome_api{
|
||||
public AutoMode autonomous_mode = AutoMode.R2D;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
@Autonomous
|
||||
public class ftc2024_auto_r2d extends LinearOpMode{
|
||||
//hi
|
||||
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();
|
||||
}
|
||||
}
|
||||
|
|
@ -19,28 +19,29 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
import com.qualcomm.robotcode.hardware.HardwareMap;
|
||||
|
||||
@Autonomous
|
||||
|
||||
public class Ftc2024_autonome_api extends LinearOpMode {
|
||||
public class Ftc2024_autonome_api{
|
||||
public enum AutoMode {
|
||||
B2D, B4D, B2N, B4N, R2D, R4D, R2N, R4N
|
||||
}
|
||||
public HardwareMap hardwareMap;
|
||||
public AutoMode autonomous_mode;
|
||||
public DcMotor lm;
|
||||
public DcMotor rm;
|
||||
public DcMotorEx lm;
|
||||
public DcMotorEx rm;
|
||||
public DcMotorEx lmelevator;
|
||||
public DcMotorEx rmelevator;
|
||||
public DcMotor harvestmotor;
|
||||
public IMU imu;
|
||||
public DcMotorEx rotation;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
boolean auto = false;
|
||||
lm = hardwareMap.get(DcMotor.class, "blm");
|
||||
rm = hardwareMap.get(DcMotor.class, "brm");
|
||||
lm = hardwareMap.get(DcMotorEx.class, "blm");
|
||||
rm = hardwareMap.get(DcMotorEx.class, "brm");
|
||||
harvestmotor = hardwareMap.get(DcMotor.class, "moissonneuse");
|
||||
rotation = hardwareMap.get(DcMotorEx.class, "elvRot");
|
||||
lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv");
|
||||
|
@ -63,17 +64,16 @@ public class Ftc2024_autonome_api extends LinearOpMode {
|
|||
imu.resetYaw();
|
||||
YawPitchRollAngles robotOrientation;
|
||||
FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this);
|
||||
autonomous_mode = AutoMode.B4D;
|
||||
|
||||
telemetry.addData("wait for start", "");
|
||||
telemetry.update();
|
||||
|
||||
|
||||
|
||||
waitForStart();
|
||||
telemetry.addData("started", "");
|
||||
while (opModeInInit()){
|
||||
imu.resetYaw();
|
||||
telemetry.addData("wait", "for start");
|
||||
telemetry.addData("Yaw", imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES));
|
||||
telemetry.update();
|
||||
robotOrientation = imu.getRobotYawPitchRollAngles();
|
||||
}
|
||||
|
||||
while (opModeIsActive()) {
|
||||
if (gamepad1.a && !auto) {
|
||||
|
@ -103,6 +103,10 @@ public class Ftc2024_autonome_api extends LinearOpMode {
|
|||
/*robot.harvest(0);
|
||||
robot.rotate((-90));
|
||||
robot.posBasse();
|
||||
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
|
||||
telemetry.addData("pos", rotation.getCurrentPosition());
|
||||
telemetry.update();
|
||||
}
|
||||
robot.forward(3.5);
|
||||
robot.harvest(-1);
|
||||
robot.backward(0.5);
|
||||
|
@ -110,7 +114,14 @@ public class Ftc2024_autonome_api extends LinearOpMode {
|
|||
robot.forward(0.5);*/
|
||||
break;
|
||||
case B2D:
|
||||
imu.resetYaw();
|
||||
|
||||
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.forward(1);
|
||||
robot.harvest(0);
|
||||
|
@ -127,6 +138,10 @@ public class Ftc2024_autonome_api extends LinearOpMode {
|
|||
robot.harvest(0);
|
||||
robot.rotate(90);
|
||||
robot.posBasse();
|
||||
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
|
||||
telemetry.addData("pos", rotation.getCurrentPosition());
|
||||
telemetry.update();
|
||||
}
|
||||
robot.forward(3.5);
|
||||
robot.harvest(-1);
|
||||
robot.backward(0.5);
|
||||
|
@ -135,16 +150,21 @@ public class Ftc2024_autonome_api extends LinearOpMode {
|
|||
break;
|
||||
case R2D:
|
||||
robot.boxElv();
|
||||
robot.harvest(1);
|
||||
robot.forward(0.5);
|
||||
robot.harvest(0);
|
||||
//rebuild
|
||||
//robot.harvest(1);
|
||||
robot.forward(1.5);
|
||||
//robot.harvest(0);
|
||||
robot.rotate(90);
|
||||
robot.posBasse();
|
||||
while (opModeIsActive() && rotation.getCurrentPosition() < rotation.getTargetPosition()) {
|
||||
telemetry.addData("pos", rotation.getCurrentPosition());
|
||||
telemetry.update();
|
||||
}
|
||||
robot.forward(1.5);
|
||||
robot.harvest(-1);
|
||||
robot.backward(0.5);
|
||||
robot.harvest(0);
|
||||
robot.forward(0.5);
|
||||
//robot.harvest(-1);
|
||||
//robot.backward(0.5);
|
||||
//robot.harvest(0);
|
||||
//robot.forward(0.5);
|
||||
break;
|
||||
case B4N:
|
||||
robot.boxElv();
|
||||
|
|
|
@ -181,6 +181,7 @@ public class WEROBOT_FTC2024_New_carlike extends LinearOpMode {
|
|||
t3 = helloexp(Math.sqrt(Math.pow(x, 2) + Math.pow(y, 2)));
|
||||
|
||||
telemetry.addData("Status", "Running");
|
||||
telemetry.addData("mode", mode);
|
||||
|
||||
|
||||
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 box", box.getCurrentPosition());
|
||||
//telemetry.addData("box velocity", rotation.getVelocity());
|
||||
//telemetry.update();
|
||||
telemetry.update();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in a new issue