Mode manuel
This commit is contained in:
parent
6eed14fe81
commit
1a0336c631
1 changed files with 33 additions and 5 deletions
36
ftc_new.java
36
ftc_new.java
|
@ -24,7 +24,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.Position;
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Velocity;
|
import org.firstinspires.ftc.robotcore.external.navigation.Velocity;
|
||||||
|
|
||||||
@TeleOp(name = "WeRobot: FTC2024 Carlike", group = "WeRobot")
|
@TeleOp(name = "WeRobot: FTC2024 Carlike", group = "WeRobot")
|
||||||
public class Werobot_FTC2024_carlike extends LinearOpMode {
|
public class WEROBOT_FTC2024_New_carlike extends LinearOpMode {
|
||||||
|
|
||||||
private DcMotor rm;
|
private DcMotor rm;
|
||||||
private DcMotor lm;
|
private DcMotor lm;
|
||||||
|
@ -64,9 +64,10 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
|
||||||
boolean already_y = false;
|
boolean already_y = false;
|
||||||
boolean already_up = false;
|
boolean already_up = false;
|
||||||
boolean already_down = false;
|
boolean already_down = false;
|
||||||
|
boolean already_ps = false;
|
||||||
|
|
||||||
boolean sinking = false;
|
boolean sinking = false;
|
||||||
|
boolean manualMode = false;
|
||||||
boolean firstLaunch = true;
|
boolean firstLaunch = true;
|
||||||
|
|
||||||
telemetry.addData("Status", "Initialized");
|
telemetry.addData("Status", "Initialized");
|
||||||
|
@ -252,6 +253,13 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
|
||||||
already_down = false;
|
already_down = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (gamepad1.ps && !already_ps){
|
||||||
|
manualMode = !manualMode;
|
||||||
|
already_ps = true;
|
||||||
|
} else if (!gamepad1.ps && already_ps){
|
||||||
|
already_ps = false;
|
||||||
|
}
|
||||||
|
|
||||||
// commentaires supprimés dans le robot
|
// commentaires supprimés dans le robot
|
||||||
// if (gamepad1.x && !already_x){
|
// if (gamepad1.x && !already_x){
|
||||||
|
|
||||||
|
@ -308,10 +316,28 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
|
||||||
|
|
||||||
|
|
||||||
// activation rotation
|
// activation rotation
|
||||||
if (!gamepad1.y && already_y) {
|
if (manualMode){
|
||||||
|
lmelevator.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
rmelevator.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
if (gamepad1.dpad_up){
|
||||||
|
rmelevator.setPower(0.3);
|
||||||
|
lmelevator.setPower(0.3);
|
||||||
|
} else if (gamepad1.dpad_down){
|
||||||
|
lmelevator.setPower(-0.3);
|
||||||
|
rmelevator.setPower(-0.3);
|
||||||
|
} else {
|
||||||
|
lmelevator.setPower(0);
|
||||||
|
rmelevator.setPower(0);
|
||||||
|
lmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
rmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!gamepad1.y && already_y && !manualMode) {
|
||||||
already_y = false;
|
already_y = false;
|
||||||
}
|
}
|
||||||
if (gamepad1.y && !already_y){
|
if (gamepad1.y && !already_y && !manualMode){
|
||||||
already_y = true;
|
already_y = true;
|
||||||
int pos = rotation.getCurrentPosition();
|
int pos = rotation.getCurrentPosition();
|
||||||
rotation.setVelocity(200);
|
rotation.setVelocity(200);
|
||||||
|
@ -338,6 +364,8 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
|
||||||
telemetry.addData("ltrigg", t);
|
telemetry.addData("ltrigg", t);
|
||||||
telemetry.addData("t2", t2);
|
telemetry.addData("t2", t2);
|
||||||
telemetry.addData("rotation power",boxRot);
|
telemetry.addData("rotation power",boxRot);
|
||||||
|
telemetry.addData("Position elevateur l", lmelevator.getCurrentPosition());
|
||||||
|
telemetry.addData("Position elevateur r", rmelevator.getCurrentPosition());
|
||||||
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());
|
||||||
|
|
Loading…
Reference in a new issue