Skip to content

Commit

Permalink
Merge pull request FIRST-Tech-Challenge#78 from blazeboy75/jackrevoy/…
Browse files Browse the repository at this point in the history
…teleop-start

Basic DriverControl/Teleop Mode
  • Loading branch information
blazeboy75 committed Nov 24, 2021
2 parents 4582332 + 46c3c56 commit ea38887
Show file tree
Hide file tree
Showing 3 changed files with 141 additions and 2 deletions.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
.setup.lock

# Don't include the already downloaded libraries
Teamcode/src/main/java/**lib/
**lib/

# Built application files
*.apk
Expand Down
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,8 @@ However, if you are an enterprising person, you may want to do things "the old-f
That's it. `gradlew` is a script that downloads Gradle and runs the commands for you, so there's no fuss! This README will be extended to contain instructions on how to run this "binary" from the command line when we figure it out.

## libOpenCvAndroid.so
For Easy Open Cv to work you have to download the `libOpenCvAndroid.so` file and copy it to the robot controller; you can find download and further instructions [here](https://github.com/OpenFTC/EasyOpenCV)
For Easy Open Cv to work you have to download the `libOpenCvAndroid.so` file and copy it to the robot controller inside of the FIRST folder; you can find download and further instructions [here](https://github.com/OpenFTC/EasyOpenCV) If there is a error you might need to rename it whatever file the error says is missing.


## Författare och meriter (Authors and credits)
### Programvaruingenjörer (Software engineers)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
package org.firstinspires.ftc.teamcode;
/** Copyright (c) 2017 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.
*/


import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;

//import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
//import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;

/** This file contains an example of an iterative (Non-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 an selection is made from the menu, the corresponding OpMode
* class is instantiated on the Robot Controller and executed.
*
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
* It includes all the skeletal structure that all iterative OpModes contain.
*
* Use Android Studios 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="Basic: Iterative OpMode", group="Iterative Opmode")
//
// @Disabled
public class StarterTeleOp extends OpMode
{
/** Declare OpMode members. */
private ElapsedTime runtime = new ElapsedTime();
private DcMotor frontL = null;
private DcMotor frontR = null;
private DcMotor backL = null;
private DcMotor backR = null;

/** Code to run ONCE when the driver hits INIT. */
@Override
public void init() {
telemetry.addData("Status", "Initializing");

/** Initialize the hardware variables. Note that the strings used here as parameters
* to 'get' must correspond to the names assigned during the robot configuration
* step (using the FTC Robot Controller app on the phone). */
frontL = hardwareMap.get(DcMotor.class, "Front Left");
frontR = hardwareMap.get(DcMotor.class, "Front Right");
backL = hardwareMap.get(DcMotor.class, "Back Left");
backR = hardwareMap.get(DcMotor.class, "Back Right");

/** Most robots need the motor on one side to be reversed to drive forward.
* Reverse the motor that runs backwards when connected directly to the battery. */
frontL.setDirection(DcMotor.Direction.FORWARD);
backL.setDirection(DcMotor.Direction.FORWARD);
frontR.setDirection(DcMotor.Direction.REVERSE);
backR.setDirection(DcMotor.Direction.REVERSE);

/** Tell the driver that initialization is complete. */
telemetry.addData("Status", "Initialized");
}

/** Code to run REPEATEDLY after the driver hits INIT, but before they hit PLAY. */
@Override
public void init_loop() {
}

/** Code to run ONCE when the driver hits PLAY. */
@Override
public void start() {
runtime.reset();
}

/** Code to run REPEATEDLY after the driver hits PLAY but before they hit STOP. */
@Override
public void loop() {
/** Setup a variable for each drive wheel to save power level for telemetry. */
double leftPower;
double rightPower;

/**POV Mode uses right stick to go forward, and left stick to turn
* will be combined in later release.
* This uses basic math to combine motions and is easier to drive straight. */
double drive = -gamepad1.left_stick_x;
double turn = gamepad1.right_stick_y;
leftPower = Range.clip(drive + turn, -1.0, 1.0) ;
rightPower = Range.clip(drive - turn, -1.0, 1.0) ;



/**Send calculated power to wheels. */
frontL.setPower(leftPower);
backL.setPower(leftPower);
frontR.setPower(rightPower);
backR.setPower(rightPower);

/** Show the elapsed game time and wheel power. */
telemetry.addData("Status", "Run Time: " + runtime.toString());
telemetry.addData("Motors", "left (%.2f), right (%.2f)", leftPower, rightPower);
}

/** Code to run ONCE after the driver hits STOP. */
@Override
public void stop() {
}

}

0 comments on commit ea38887

Please sign in to comment.