-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathBetterSample.java
More file actions
258 lines (218 loc) · 11.9 KB
/
BetterSample.java
File metadata and controls
258 lines (218 loc) · 11.9 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
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
/* Copyright (c) 2021 FIRST. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted (subject to the limitations in the disclaimer below) provided that
* the following conditions are met:
*
* Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
* promote products derived from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import io.github.harpolewillow.turnedaxismecanum.TurnedAxisMecanum;
import io.github.harpolewillow.complexkebabcalculator.ComplexKebabCalculator;
/**
* This file contains an example of a Linear "OpMode".
* An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match.
* The names of OpModes appear on the menu of the FTC Driver Station.
* When a selection is made from the menu, the corresponding OpMode is executed.
*
* This particular OpMode illustrates driving a 4-motor Omni-Directional (or Holonomic) robot.
* This code will work with either a Mecanum-Drive or an X-Drive train.
* Both of these drives are illustrated at https://gm0.org/en/latest/docs/robot-design/drivetrains/holonomic.html
* Note that a Mecanum drive must display an X roller-pattern when viewed from above.
*
* Also note that it is critical to set the correct rotation direction for each motor. See details below.
*
* Holonomic drives provide the ability for the robot to move in three axes (directions) simultaneously.
* Each motion axis is controlled by one Joystick axis.
*
* 1) Axial: Driving forward and backward Left-joystick Forward/Backward
* 2) Lateral: Strafing right and left Left-joystick Right and Left
* 3) Yaw: Rotating Clockwise and counter clockwise Right-joystick Right and Left
*
* This code is written assuming that the right-side motors need to be reversed for the robot to drive forward.
* When you first test your robot, if it moves backward when you push the left stick forward, then you must flip
* the direction of all 4 motors (see code below).
*
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
*/
@TeleOp(name="Advanced: Omni Linear OpMode2866", group="Linear Opmode")
public class BetterSample extends LinearOpMode {
// Declare OpMode members for each of the 4 motors.
private ElapsedTime runtime = new ElapsedTime();
private DcMotorEx leftFrontDrive = null;
private DcMotorEx leftBackDrive = null;
private DcMotorEx rightFrontDrive = null;
private DcMotorEx rightBackDrive = null;
private DcMotorEx kebab = null; // this is the launcher thingamajig
private DcMotorEx intake = null;
private double kebabSpeed = 0.0;
//private Servo pusher = null;
//private Servo mysteryservo = null; // barrier in the front I
//private Servo mysteryservo2 = null; // barrier in the front II
/*
servo modes
0: default
1: +45 degrees
2: +90 degrees
*/
WheelRounder rounder_of_wheels = new WheelRounder(.15);
ComplexKebabCalculator complexKebabCalculator = new ComplexKebabCalculator(.7);
TurnedAxisMecanum turnedAxisMecanum = new TurnedAxisMecanum();
@Override
public void runOpMode() {
// Initialize the hardware variables. Note that the strings used here must correspond
// to the names assigned during the robot configuration step on the DS or RC devices.
leftFrontDrive = hardwareMap.get(DcMotorEx.class, "left_front_drive");
leftBackDrive = hardwareMap.get(DcMotorEx.class, "left_back_drive");
rightFrontDrive = hardwareMap.get(DcMotorEx.class, "right_front_drive");
rightBackDrive = hardwareMap.get(DcMotorEx.class, "right_back_drive");
kebab = hardwareMap.get(DcMotorEx.class, "kebab_launcher");
intake = hardwareMap.get(DcMotorEx.class, "intake");
//pusher = hardwareMap.get(Servo.class, "pusher");
//mysteryservo = hardwareMap.get(Servo.class, "mysteryservo");
// ########################################################################################
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
// ########################################################################################
// Most robots need the motors on one side to be reversed to drive forward.
// The motor reversals shown here are for a "direct drive" robot (the wheels turn the same direction as the motor shaft)
// If your robot has additional gear reductions or uses a right-angled drive, it's important to ensure
// that your motors are turning in the correct direction. So, start out with the reversals here, BUT
// when you first test your robot, push the left joystick forward and observe the direction the wheels turn.
// Reverse the direction (flip FORWARD <-> REVERSE ) of any wheel that runs backward
// Keep testing until ALL the wheels move the robot forward when you push the left joystick forward.
leftFrontDrive.setDirection(DcMotor.Direction.REVERSE);
leftBackDrive.setDirection(DcMotor.Direction.REVERSE);
rightFrontDrive.setDirection(DcMotor.Direction.FORWARD);
rightBackDrive.setDirection(DcMotor.Direction.FORWARD);
// Wait for the game to start (driver presses PLAY)
telemetry.addData("Status", "Initialized");
telemetry.update();
waitForStart();
runtime.reset();
boolean prior_press = false;
boolean button_press = false;
// run until the end of the match (driver presses STOP)
while (opModeIsActive()) {
double max;
// POV Mode uses left joystick to go forward & strafe, and right joystick to rotate.
double axial = -gamepad1.left_stick_y; // Note: pushing stick forward gives negative value
double lateral = gamepad1.left_stick_x;
double yaw = gamepad1.right_stick_x;
RevisedWheelControls movement_calculator = new RevisedWheelControls();
double[] wheel_motions = movement_calculator.calculate(gamepad1.left_stick_x,gamepad1.left_stick_y,gamepad1.right_stick_x,gamepad1.right_stick_y);
/*
// Normalize the values so no wheel power exceeds 100%
// This ensures that the robot maintains the desired motion.
max = Math.max(Math.abs(leftFrontPower), Math.abs(rightFrontPower));
max = Math.max(max, Math.abs(leftBackPower));
max = Math.max(max, Math.abs(rightBackPower));
if (max > 1.0) {
leftFrontPower /= max;
rightFrontPower /= max;
leftBackPower /= max;
rightBackPower /= max;
}
*/
double[][] joystickValues =
{
new double[] {gamepad1.left_stick_x, gamepad1.left_stick_y},
new double[] {gamepad1.right_stick_x, gamepad1.right_stick_y}
};
double[][] wheelValues = turnedAxisMecanum.calculate(joystickValues);
double leftFrontPower = wheelValues[0][0];
double leftBackPower = wheelValues[0][1];
double rightFrontPower = wheelValues[1][0];
double rightBackPower = wheelValues[1][1];
/*
kebabcomp Kebab_Calculator = new kebabcomp();
boolean[] Kebab_Buttons = {gamepad1.b||gamepad2.b, gamepad1.x||gamepad2.x, gamepad1.a||gamepad2.a, gamepad1.y||gamepad2.y};
kebabSpeed = Kebab_Calculator.new_speed(kebabSpeed, Kebab_Buttons);
kebab.setPower(kebabSpeed);
*/
complexKebabCalculator.opMode=this;
kebabSpeed = complexKebabCalculator.calculate(gamepad1.y||gamepad2.y, gamepad1.x||gamepad2.x, gamepad1.a||gamepad2.a, gamepad1.b||gamepad2.b);
kebab.setPower(kebabSpeed*.97);
telemetry.addLine(kebabSpeed+"");
/*
if (gamepad2.left_trigger>0) {
intake.setPower(1);
leftFrontPower = 0.0;
rightFrontPower = 0.0;
leftBackPower = 0.0;
rightBackPower = 0.0;
}
else if (gamepad2.right_trigger>0) {
intake.setPower(-1);
leftFrontPower = 0.0;
rightFrontPower = 0.0;
leftBackPower = 0.0;
rightBackPower = 0.0;
}
else {intake.setPower(0);}
if ((gamepad1.right_trigger==1)||(gamepad2.right_trigger==1))
{
//mysteryservo2.setPosition(.5);
leftFrontPower = 0.0;
rightFrontPower = 0.0;
leftBackPower = 0.0;
rightBackPower = 0.0;
}
else {
/*mysteryservo2.setPosition(0.145);*/
//}
//*/
if ((gamepad1.dpad_up)||(gamepad2.dpad_up)) {
intake.setPower(1);
}
else if ((gamepad1.dpad_down)||(gamepad2.dpad_down)) {
intake.setPower(-1);
}
else {intake.setPower(0);}
if (gamepad1.right_trigger>0) {
leftFrontPower = 0.0;
rightFrontPower = 0.0;
leftBackPower = 0.0;
rightBackPower = 0.0;
}
double correction = -0.07;
// Send calculated power to wheels
leftFrontDrive.setPower(leftFrontPower);
rightFrontDrive.setPower(rightFrontPower);
leftBackDrive.setPower(leftBackPower);
rightBackDrive.setPower(rightBackPower);
// Show the elapsed game time and wheel power.
telemetry.addData("Status", "Run Time: " + runtime.toString());
telemetry.addData("Front left/Right", "%4.2f, %4.2f", leftFrontPower, rightFrontPower);
telemetry.addData("Back left/Right", "%4.2f, %4.2f", leftBackPower, rightBackPower);
telemetry.update();
}
}
}