-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathlastmatch.java
More file actions
148 lines (126 loc) · 5.87 KB
/
lastmatch.java
File metadata and controls
148 lines (126 loc) · 5.87 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
package org.firstinspires.ftc.teamcode;
//import FTC2024WeRobotControl; //a tester car pas sur que ça fonctionne
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.hardware.DcMotorEx;
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.Orientation;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
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;
@Autonomous
public class lastmatch extends LinearOpMode {
public DcMotorEx lm;
public DcMotorEx rm;
public DcMotorEx lmelevator;
public DcMotorEx rmelevator;
public DcMotor harvestmotor;
public IMU imu;
public DcMotorEx rotation;
private ElapsedTime timer;
@Override
public void runOpMode() {
timer = new ElapsedTime();
boolean auto = false;
lm = hardwareMap.get(DcMotorEx.class, "blm");
rm = hardwareMap.get(DcMotorEx.class, "brm");
harvestmotor = hardwareMap.get(DcMotor.class, "moissonneuse");
rotation = hardwareMap.get(DcMotorEx.class, "elvRot");
rotation.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lmelevator = hardwareMap.get(DcMotorEx.class, "ltrselv");
lmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
lmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rmelevator = hardwareMap.get(DcMotorEx.class, "rtrselv");
rmelevator.setDirection(DcMotor.Direction.REVERSE);
rmelevator.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rmelevator.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rm.setDirection(DcMotor.Direction.REVERSE);
rotation.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
imu = hardwareMap.get(IMU.class, "imu");
imu.initialize(
new IMU.Parameters(
new RevHubOrientationOnRobot(
RevHubOrientationOnRobot.LogoFacingDirection.UP,
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)));
imu.resetYaw();
YawPitchRollAngles robotOrientation;
FTC2024WeRobotControl robot = new FTC2024WeRobotControl(this);
telemetry.addData("wait for start", "");
telemetry.update();
waitForStart();
telemetry.addData("started", "");
telemetry.update();
robotOrientation = imu.getRobotYawPitchRollAngles();
while (opModeIsActive()) {
if (gamepad1.a && !auto) {
auto = true;
break;
}
}
if (opModeIsActive()) {
double motor_speed = 1.0;
lmelevator.setVelocity(600);
rmelevator.setVelocity(600);
lmelevator.setTargetPosition(200);
rmelevator.setTargetPosition(200);
rotation.setVelocity(600);
rotation.setTargetPosition(40);
lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
sleep(2000);
lm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
double total_time = robot.time_for_dist(1 * robot.ground_tiles_width, Math.abs(motor_speed));
timer.reset();
while (opModeIsActive() && timer.seconds() < total_time) {
lm.setPower(motor_speed);
rm.setPower(motor_speed);
}
lm.setPower(0);
rm.setPower(0);
harvestmotor.setPower(-0.6);
lm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
total_time = robot.time_for_dist(0.7 * robot.ground_tiles_width, Math.abs(motor_speed));
timer.reset();
while (opModeIsActive() && timer.seconds() < total_time) {
lm.setPower(-motor_speed);
rm.setPower(-motor_speed);
}
lm.setPower(0);
rm.setPower(0);
double angle = 90.0;
lm.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rm.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
double perimeter = Math.toRadians(angle)* 37.0/2.0;
int targetPos = (int) Math.floor(perimeter/(9e-2*Math.PI));
targetPos = targetPos * 20;
rm.setTargetPosition(targetPos);
lm.setTargetPosition(-targetPos);
lm.setVelocity(600);
rm.setVelocity(600);
lm.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rm.setMode(DcMotor.RunMode.RUN_TO_POSITION);
// while (Math.abs(lm.getCurrentPosition() - targetPos)>=2){}
motor_speed= 1;
lm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
total_time = robot.time_for_dist(1.5 * robot.ground_tiles_width, Math.abs(motor_speed));
timer.reset();
while (opModeIsActive() && timer.seconds() < total_time) {
lm.setPower(motor_speed);
rm.setPower(motor_speed);
}
lm.setPower(0);
rm.setPower(0);
}
}
}