|
| 1 | +/* Copyright (c) 2021 FIRST. All rights reserved. |
| 2 | + * |
| 3 | + * Redistribution and use in source and binary forms, with or without modification, |
| 4 | + * are permitted (subject to the limitations in the disclaimer below) provided that |
| 5 | + * the following conditions are met: |
| 6 | + * |
| 7 | + * Redistributions of source code must retain the above copyright notice, this list |
| 8 | + * of conditions and the following disclaimer. |
| 9 | + * |
| 10 | + * Redistributions in binary form must reproduce the above copyright notice, this |
| 11 | + * list of conditions and the following disclaimer in the documentation and/or |
| 12 | + * other materials provided with the distribution. |
| 13 | + * |
| 14 | + * Neither the name of FIRST nor the names of its contributors may be used to endorse or |
| 15 | + * promote products derived from this software without specific prior written permission. |
| 16 | + * |
| 17 | + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS |
| 18 | + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 19 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, |
| 20 | + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 21 | + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE |
| 22 | + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL |
| 23 | + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR |
| 24 | + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 25 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, |
| 26 | + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
| 27 | + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
| 28 | + */ |
| 29 | + |
| 30 | +package org.firstinspires.ftc.robotcontroller.external.samples; |
| 31 | + |
| 32 | +import com.qualcomm.robotcore.eventloop.opmode.Disabled; |
| 33 | +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; |
| 34 | +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; |
| 35 | +import com.qualcomm.robotcore.hardware.DcMotor; |
| 36 | +import com.qualcomm.robotcore.util.ElapsedTime; |
| 37 | + |
| 38 | +/** |
| 39 | + * This file contains an example of a Linear "OpMode". |
| 40 | + * An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match. |
| 41 | + * The names of OpModes appear on the menu of the FTC Driver Station. |
| 42 | + * When a selection is made from the menu, the corresponding OpMode is executed. |
| 43 | + * |
| 44 | + * This particular OpMode illustrates driving a 4-motor Omni-Directional (or Holonomic) robot. |
| 45 | + * This code will work with either a Mecanum-Drive or an X-Drive train. |
| 46 | + * Both of these drives are illustrated at https://gm0.org/en/latest/docs/robot-design/drivetrains/holonomic.html |
| 47 | + * Note that a Mecanum drive must display an X roller-pattern when viewed from above. |
| 48 | + * |
| 49 | + * Holonomic drives provide the ability for the robot to move in three axes (directions) simultaneously. |
| 50 | + * Each motion axis is controlled by one Joystick axis. |
| 51 | + * |
| 52 | + * 1) Axial: Driving forward and backwards Left-joystick Forward/Backwards |
| 53 | + * 2) Lateral: Strafing right and left Left-joystick Right and Left |
| 54 | + * 3) Yaw: Rotating Clockwise and counter clockwise Right-joystick Right and Left |
| 55 | + * |
| 56 | + * This code is written assuming that the right-side motors need to be reversed for the robot to drive forward. |
| 57 | + * When you first test your robot, if it moves backwards when you push the left stick forward, then you must flip |
| 58 | + * the direction of all 4 motors (see code below). |
| 59 | + * |
| 60 | + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. |
| 61 | + * Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list |
| 62 | + */ |
| 63 | + |
| 64 | +@TeleOp(name="Basic: Omni Linear OpMode", group="Linear Opmode") |
| 65 | +@Disabled |
| 66 | +public class BasicOmniOpMode_Linear extends LinearOpMode { |
| 67 | + |
| 68 | + // Declare OpMode members for each of the 4 motors. |
| 69 | + private ElapsedTime runtime = new ElapsedTime(); |
| 70 | + private DcMotor leftFrontDrive = null; |
| 71 | + private DcMotor leftBackDrive = null; |
| 72 | + private DcMotor rightFrontDrive = null; |
| 73 | + private DcMotor rightBackDrive = null; |
| 74 | + |
| 75 | + @Override |
| 76 | + public void runOpMode() { |
| 77 | + |
| 78 | + // Initialize the hardware variables. Note that the strings used here must correspond |
| 79 | + // to the names assigned during the robot configuration step on the DS or RC devices. |
| 80 | + leftFrontDrive = hardwareMap.get(DcMotor.class, "left_front_drive"); |
| 81 | + leftBackDrive = hardwareMap.get(DcMotor.class, "left_back_drive"); |
| 82 | + rightFrontDrive = hardwareMap.get(DcMotor.class, "right_front_drive"); |
| 83 | + rightBackDrive = hardwareMap.get(DcMotor.class, "right_back_drive"); |
| 84 | + |
| 85 | + // Most robots need the motors on one side to be reversed to drive forward. |
| 86 | + // When you first test your robot, push the left joystick forward |
| 87 | + // and flip the direction ( FORWARD <-> REVERSE ) of any wheel that runs backwards |
| 88 | + leftFrontDrive.setDirection(DcMotor.Direction.REVERSE); |
| 89 | + leftBackDrive.setDirection(DcMotor.Direction.REVERSE); |
| 90 | + rightFrontDrive.setDirection(DcMotor.Direction.FORWARD); |
| 91 | + rightBackDrive.setDirection(DcMotor.Direction.FORWARD); |
| 92 | + |
| 93 | + // Wait for the game to start (driver presses PLAY) |
| 94 | + telemetry.addData("Status", "Initialized"); |
| 95 | + telemetry.update(); |
| 96 | + |
| 97 | + waitForStart(); |
| 98 | + runtime.reset(); |
| 99 | + |
| 100 | + // run until the end of the match (driver presses STOP) |
| 101 | + while (opModeIsActive()) { |
| 102 | + double max; |
| 103 | + |
| 104 | + // POV Mode uses left joystick to go forward & strafe, and right joystick to rotate. |
| 105 | + double axial = -gamepad1.left_stick_y; // Note: pushing stick forward gives negative value |
| 106 | + double lateral = gamepad1.left_stick_x; |
| 107 | + double yaw = gamepad1.right_stick_x; |
| 108 | + |
| 109 | + // Combine the joystick requests for each axis-motion to determine each wheel's power. |
| 110 | + // Set up a variable for each drive wheel to save the power level for telemetry. |
| 111 | + double leftFrontPower = axial + lateral + yaw; |
| 112 | + double rightFrontPower = axial - lateral - yaw; |
| 113 | + double leftBackPower = axial - lateral + yaw; |
| 114 | + double rightBackPower = axial + lateral - yaw; |
| 115 | + |
| 116 | + // Normalize the values so no wheel power exceeds 100% |
| 117 | + // This ensures that the robot maintains the desired motion. |
| 118 | + max = Math.max(Math.abs(leftFrontPower), Math.abs(rightFrontPower)); |
| 119 | + max = Math.max(max, Math.abs(leftBackPower)); |
| 120 | + max = Math.max(max, Math.abs(rightBackPower)); |
| 121 | + |
| 122 | + if (max > 1.0) { |
| 123 | + leftFrontPower /= max; |
| 124 | + rightFrontPower /= max; |
| 125 | + leftBackPower /= max; |
| 126 | + rightBackPower /= max; |
| 127 | + } |
| 128 | + |
| 129 | + // This is test code: |
| 130 | + // |
| 131 | + // Uncomment the following code to test your motor directions. |
| 132 | + // Each button should make the corresponding motor run FORWARD. |
| 133 | + // 1) First get all the motors to take to correct positions on the robot |
| 134 | + // by adjusting your Robot Configuration if necessary. |
| 135 | + // 2) Then make sure they run in the correct direction by modifying the |
| 136 | + // the setDirection() calls above. |
| 137 | + // Once the correct motors move in the correct direction re-comment this code. |
| 138 | + |
| 139 | + /* |
| 140 | + leftFrontPower = gamepad1.x ? 1.0 : 0.0; // X gamepad |
| 141 | + leftBackPower = gamepad1.a ? 1.0 : 0.0; // A gamepad |
| 142 | + rightFrontPower = gamepad1.y ? 1.0 : 0.0; // Y gamepad |
| 143 | + rightBackPower = gamepad1.b ? 1.0 : 0.0; // B gamepad |
| 144 | + */ |
| 145 | + |
| 146 | + // Send calculated power to wheels |
| 147 | + leftFrontDrive.setPower(leftFrontPower); |
| 148 | + rightFrontDrive.setPower(rightFrontPower); |
| 149 | + leftBackDrive.setPower(leftBackPower); |
| 150 | + rightBackDrive.setPower(rightBackPower); |
| 151 | + |
| 152 | + // Show the elapsed game time and wheel power. |
| 153 | + telemetry.addData("Status", "Run Time: " + runtime.toString()); |
| 154 | + telemetry.addData("Front left/Right", "%4.2f, %4.2f", leftFrontPower, rightFrontPower); |
| 155 | + telemetry.addData("Back left/Right", "%4.2f, %4.2f", leftBackPower, rightBackPower); |
| 156 | + telemetry.update(); |
| 157 | + } |
| 158 | + }} |
0 commit comments