-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathTeleOp6128.java
More file actions
170 lines (144 loc) · 7.62 KB
/
TeleOp6128.java
File metadata and controls
170 lines (144 loc) · 7.62 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
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.util.Range;
@TeleOp(name = "TeleOp6128", group = "Official")
public class TeleOp6128 extends LinearOpMode {
private Config6128 robot = new Config6128(this);
public void runOpMode() {
// Initialize the robot
robot.ConfigureRobtHardware();
//Motor Power
double speedTurn=1,speedMove=1,speedSide=1;
double slowTurn = 0.3, slowMove=0.3,slowSide=0.3;
double regTurn = 0.6, regMove=0.6,regSide=1;
boolean slowMode=false, powerMode=false;
double powerUp=1.3;
//servo position/
waitForStart();
while (opModeIsActive()) {
//lift test
double liftPower=gamepad1.left_stick_y;
if (gamepad1.left_stick_button){
liftPower=liftPower*0.4;
}
if (robot.lift_sensor.getState()==true){
robot.lift_right.setPower(liftPower);
robot.lift_left.setPower(liftPower);
}else {
if(gamepad1.left_stick_y<-0.1){
robot.lift_right.setPower(liftPower);
robot.lift_left.setPower(liftPower);
}else {
robot.lift_left.setPower(0);
robot.lift_right.setPower(0);
}
}
//Power up function
if (gamepad2.right_bumper){
powerMode=true;
slowMode=false;
}else{
powerMode=false;
if (gamepad2.left_bumper){
slowMode=true;
}else{
slowMode=false;
}
}
double driveForward = gamepad2.left_stick_y * speedMove, driveRightSide = gamepad2.left_stick_x * speedSide,
turnRight = -gamepad2.right_stick_x * speedTurn;
double intakePower=gamepad1.left_trigger-gamepad1.right_trigger;
//prevent small input from stick
driveForward = (driveForward >= -0.1 && driveForward <= 0.1) ? 0 : driveForward;
driveRightSide = (driveRightSide >= -0.1 && driveRightSide <= 0.1) ? 0 : driveRightSide;
turnRight = (turnRight >= -0.1 && turnRight <= 0.1) ? 0 : turnRight;
if (gamepad2.dpad_left){
driveRightSide=-1*speedSide;
}
if (gamepad2.dpad_right){
driveRightSide=1*speedSide;
}
if(gamepad2.dpad_up){
driveForward=1*speedMove;
}
if(gamepad2.dpad_down){
driveForward=-1*speedMove;
}
// Send calculated power to wheels
if (gamepad2.left_trigger<=0.1&&gamepad2.right_trigger<=0.1){
if (slowMode){
robot.left_front.setPower(Range.clip((-driveRightSide*slowSide + driveForward*slowMove + turnRight*slowTurn), -1.0, 1.0));
robot.right_front.setPower(Range.clip((driveRightSide*slowSide + driveForward*slowMove - turnRight*slowTurn), -1.0, 1.0));
robot.left_back.setPower(Range.clip((driveRightSide*slowSide + driveForward*slowMove + turnRight*slowTurn), -1.0, 1.0));
robot.right_back.setPower(Range.clip((-driveRightSide*slowSide + driveForward*slowMove - turnRight*slowTurn), -1.0, 1.0));
}else if(!powerMode){
robot.left_front.setPower(Range.clip((-driveRightSide*regSide + driveForward*regMove + turnRight*regTurn), -1.0, 1.0));
robot.right_front.setPower(Range.clip((driveRightSide*regSide + driveForward*regMove - turnRight*regTurn), -1.0, 1.0));
robot.left_back.setPower(Range.clip((driveRightSide*regSide + driveForward*regMove + turnRight*regTurn), -1.0, 1.0));
robot.right_back.setPower(Range.clip((-driveRightSide*regSide + driveForward*regMove - turnRight*regTurn), -1.0, 1.0));
}else{
robot.left_front.setPower(Range.clip((-driveRightSide + driveForward + turnRight), -1.0, 1.0));
robot.right_front.setPower(Range.clip((driveRightSide + driveForward - turnRight), -1.0, 1.0));
robot.left_back.setPower(Range.clip((driveRightSide + driveForward + turnRight), -1.0, 1.0));
robot.right_back.setPower(Range.clip((-driveRightSide + driveForward - turnRight), -1.0, 1.0));
}
}else{
if (gamepad2.left_trigger>=0.1){
robot.left_front.setPower(Range.clip((gamepad2.left_trigger), -1.0, 1.0));
robot.right_front.setPower(Range.clip((-gamepad2.left_trigger), -1.0, 1.0));
robot.left_back.setPower(Range.clip((-gamepad2.left_trigger), -1.0, 1.0));
robot.right_back.setPower(Range.clip((gamepad2.left_trigger), -1.0, 1.0));
}
if (gamepad2.right_trigger>=0.1){
robot.left_front.setPower(Range.clip((-gamepad2.right_trigger), -1.0, 1.0));
robot.right_front.setPower(Range.clip((gamepad2.right_trigger), -1.0, 1.0));
robot.left_back.setPower(Range.clip((gamepad2.right_trigger), -1.0, 1.0));
robot.right_back.setPower(Range.clip((-gamepad2.right_trigger), -1.0, 1.0));
}
}
robot.intake_left.setPower(intakePower);
robot.intake_right.setPower(intakePower);
if (gamepad1.right_bumper){
robot.servo_2.setPosition(robot.r2_squ);
robot.servo_3.setPosition(robot.l3_squ);
}
if ((gamepad1.right_trigger>0)&&(gamepad1.right_bumper==false)){
robot.servo_2.setPosition(robot.r2_in);
robot.servo_3.setPosition(robot.l3_in);
}
if (gamepad1.left_bumper){
robot.servo_2.setPosition(robot.r2_out);
robot.servo_3.setPosition(robot.l3_out);
}
if (gamepad1.a){
robot.servo_0.setPosition(robot.r0_down);
robot.servo_1.setPosition(robot.l1_down);
}
if (gamepad1.b){
robot.servo_0.setPosition(robot.r0_middle);
robot.servo_1.setPosition(robot.l1_middle);
}
if(gamepad1.x){
robot.servo_0.setPosition(robot.r0_up);
robot.servo_1.setPosition(robot.l1_up);
}
//robot.servo_2.setPosition(gamepad1.left_trigger);
//robot.servo_3.setPosition(gamepad1.right_trigger);
telemetry.addData("left button",robot.left_button.getState())
.addData("right button",robot.right_button.getState());
telemetry.addData("lift_right power",robot.lift_right.getPower())
.addData("lift_left power",robot.lift_left.getPower())
.addData("intake power",intakePower)
.addData("intake_right",robot.intake_right.getPower())
.addData("intake_left",robot.intake_left.getPower());
telemetry.addData("Lf power", robot.left_front.getPower())
.addData("Rf power", robot.right_front.getPower())
.addData("Lb power", robot.left_back.getPower())
.addData("Rb power", robot.right_back.getPower());
telemetry.addData("R2 servo",robot.servo_2.getPosition())
.addData("L3 servo",robot.servo_3.getPosition());
telemetry.update();
}
}
}