This repository has been archived by the owner on Oct 27, 2020. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 3.2k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
119 changed files
with
3,700 additions
and
2,354 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 1,6 @@ | ||
<?xml version='1.0' encoding='UTF-8'?> | ||
<QCARConfig> | ||
<Tracking> | ||
<VuMark name="RelicRecovery" size="304.80000376701355 223.630235354" /> | ||
</Tracking> | ||
</QCARConfig> |
139 changes: 139 additions & 0 deletions
139
...in/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 1,139 @@ | ||
/* 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. | ||
*/ | ||
|
||
package org.firstinspires.ftc.robotcontroller.external.samples; | ||
|
||
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.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 BasicOpMode_Iterative extends OpMode | ||
{ | ||
// Declare OpMode members. | ||
private ElapsedTime runtime = new ElapsedTime(); | ||
private DcMotor leftDrive = null; | ||
private DcMotor rightDrive = null; | ||
|
||
/* | ||
* Code to run ONCE when the driver hits INIT | ||
*/ | ||
@Override | ||
public void init() { | ||
telemetry.addData("Status", "Initialized"); | ||
|
||
// 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). | ||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive"); | ||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive"); | ||
|
||
// 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 | ||
leftDrive.setDirection(DcMotor.Direction.FORWARD); | ||
rightDrive.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; | ||
|
||
// Choose to drive using either Tank Mode, or POV Mode | ||
// Comment out the method that's not used. The default below is POV. | ||
|
||
// POV Mode uses left stick to go forward, and right stick to turn. | ||
// - This uses basic math to combine motions and is easier to drive straight. | ||
double drive = -gamepad1.left_stick_y; | ||
double turn = gamepad1.right_stick_x; | ||
leftPower = Range.clip(drive turn, -1.0, 1.0) ; | ||
rightPower = Range.clip(drive - turn, -1.0, 1.0) ; | ||
|
||
// Tank Mode uses one stick to control each wheel. | ||
// - This requires no math, but it is hard to drive forward slowly and keep straight. | ||
// leftPower = -gamepad1.left_stick_y ; | ||
// rightPower = -gamepad1.right_stick_y ; | ||
|
||
// Send calculated power to wheels | ||
leftDrive.setPower(leftPower); | ||
rightDrive.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() { | ||
} | ||
|
||
} |
114 changes: 114 additions & 0 deletions
114
.../main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 1,114 @@ | ||
/* 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. | ||
*/ | ||
|
||
package org.firstinspires.ftc.robotcontroller.external.samples; | ||
|
||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; | ||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; | ||
import com.qualcomm.robotcore.eventloop.opmode.Disabled; | ||
import com.qualcomm.robotcore.hardware.DcMotor; | ||
import com.qualcomm.robotcore.util.ElapsedTime; | ||
import com.qualcomm.robotcore.util.Range; | ||
|
||
|
||
/** | ||
* This file contains an minimal 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 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 linear 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: Linear OpMode", group="Linear Opmode") | ||
@Disabled | ||
public class BasicOpMode_Linear extends LinearOpMode { | ||
|
||
// Declare OpMode members. | ||
private ElapsedTime runtime = new ElapsedTime(); | ||
private DcMotor leftDrive = null; | ||
private DcMotor rightDrive = null; | ||
|
||
@Override | ||
public void runOpMode() { | ||
telemetry.addData("Status", "Initialized"); | ||
telemetry.update(); | ||
|
||
// 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). | ||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive"); | ||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive"); | ||
|
||
// 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 | ||
leftDrive.setDirection(DcMotor.Direction.FORWARD); | ||
rightDrive.setDirection(DcMotor.Direction.REVERSE); | ||
|
||
// Wait for the game to start (driver presses PLAY) | ||
waitForStart(); | ||
runtime.reset(); | ||
|
||
// run until the end of the match (driver presses STOP) | ||
while (opModeIsActive()) { | ||
|
||
// Setup a variable for each drive wheel to save power level for telemetry | ||
double leftPower; | ||
double rightPower; | ||
|
||
// Choose to drive using either Tank Mode, or POV Mode | ||
// Comment out the method that's not used. The default below is POV. | ||
|
||
// POV Mode uses left stick to go forward, and right stick to turn. | ||
// - This uses basic math to combine motions and is easier to drive straight. | ||
double drive = -gamepad1.left_stick_y; | ||
double turn = gamepad1.right_stick_x; | ||
leftPower = Range.clip(drive turn, -1.0, 1.0) ; | ||
rightPower = Range.clip(drive - turn, -1.0, 1.0) ; | ||
|
||
// Tank Mode uses one stick to control each wheel. | ||
// - This requires no math, but it is hard to drive forward slowly and keep straight. | ||
// leftPower = -gamepad1.left_stick_y ; | ||
// rightPower = -gamepad1.right_stick_y ; | ||
|
||
// Send calculated power to wheels | ||
leftDrive.setPower(leftPower); | ||
rightDrive.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); | ||
telemetry.update(); | ||
} | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.