Compare commits
9 Commits
Branch-Ash
...
9e8609e68d
Author | SHA1 | Date | |
---|---|---|---|
9e8609e68d | |||
832de95fc1 | |||
63158215d0 | |||
6e6e626816 | |||
b5aca8b93c | |||
8a0aa126b6 | |||
6938e09b2b | |||
e86c31771e | |||
0baf961680 |
@ -23,7 +23,17 @@ android {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
repositories {
|
||||||
|
maven {
|
||||||
|
url = 'https://maven.brott.dev/'
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation project(':FtcRobotController')
|
implementation project(':FtcRobotController')
|
||||||
annotationProcessor files('lib/OpModeAnnotationProcessor.jar')
|
annotationProcessor files('lib/OpModeAnnotationProcessor.jar')
|
||||||
|
implementation "com.acmerobotics.roadrunner:ftc:0.1.12"
|
||||||
|
implementation "com.acmerobotics.roadrunner:core:1.0.0-beta8"
|
||||||
|
implementation "com.acmerobotics.roadrunner:actions:1.0.0-beta8"
|
||||||
|
implementation "com.acmerobotics.dashboard:dashboard:0.4.14"
|
||||||
}
|
}
|
||||||
|
@ -0,0 +1,78 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
|
import android.util.Size;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.firstinspires.ftc.vision.VisionPortal;
|
||||||
|
|
||||||
|
import java.util.Locale;
|
||||||
|
|
||||||
|
@TeleOp(name = "CometBots Camera Demo (HDMI)", group = "[14493] CometBots")
|
||||||
|
public class CometBotsCameraDemo extends LinearOpMode {
|
||||||
|
|
||||||
|
final boolean USING_WEBCAM = true;
|
||||||
|
final BuiltinCameraDirection INTERNAL_CAM_DIR = BuiltinCameraDirection.FRONT;
|
||||||
|
final int RESOLUTION_WIDTH = 640;
|
||||||
|
final int RESOLUTION_HEIGHT = 480;
|
||||||
|
|
||||||
|
// Internal state
|
||||||
|
boolean lastX;
|
||||||
|
int frameCount;
|
||||||
|
long capReqTime;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
telemetry.speak("Development - Camera Test");
|
||||||
|
|
||||||
|
VisionPortal portal;
|
||||||
|
|
||||||
|
if (USING_WEBCAM)
|
||||||
|
{
|
||||||
|
portal = new VisionPortal.Builder()
|
||||||
|
.setCamera(hardwareMap.get(WebcamName.class, "watch out"))
|
||||||
|
.setCameraResolution(new Size(RESOLUTION_WIDTH, RESOLUTION_HEIGHT))
|
||||||
|
.build();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
portal = new VisionPortal.Builder()
|
||||||
|
.setCamera(INTERNAL_CAM_DIR)
|
||||||
|
.setCameraResolution(new Size(RESOLUTION_WIDTH, RESOLUTION_HEIGHT))
|
||||||
|
.build();
|
||||||
|
}
|
||||||
|
|
||||||
|
while (!isStopRequested())
|
||||||
|
{
|
||||||
|
boolean x = gamepad1.x;
|
||||||
|
|
||||||
|
if (x && !lastX)
|
||||||
|
{
|
||||||
|
portal.saveNextFrameRaw(String.format(Locale.US, "CameraFrameCapture-%06d", frameCount++));
|
||||||
|
capReqTime = System.currentTimeMillis();
|
||||||
|
}
|
||||||
|
|
||||||
|
lastX = x;
|
||||||
|
|
||||||
|
telemetry.addLine("######## Camera Capture Utility ########");
|
||||||
|
telemetry.addLine(String.format(Locale.US, " > Resolution: %dx%d", RESOLUTION_WIDTH, RESOLUTION_HEIGHT));
|
||||||
|
telemetry.addLine(" > Press X (or Square) to capture a frame");
|
||||||
|
telemetry.addData(" > Camera Status", portal.getCameraState());
|
||||||
|
|
||||||
|
if (capReqTime != 0)
|
||||||
|
{
|
||||||
|
telemetry.addLine("\nCaptured Frame!");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (capReqTime != 0 && System.currentTimeMillis() - capReqTime > 1000)
|
||||||
|
{
|
||||||
|
capReqTime = 0;
|
||||||
|
}
|
||||||
|
telemetry.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,72 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
|
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
import com.qualcomm.robotcore.hardware.IMU;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
||||||
|
|
||||||
|
@TeleOp(name = "CometBots IMU Demo", group = "[14493] CometBots")
|
||||||
|
public class CometBotsIMUDemo extends LinearOpMode {
|
||||||
|
|
||||||
|
IMU imu;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
// Retrieve and initialize the IMU.
|
||||||
|
// This sample expects the IMU to be in a REV Hub and named "imu".
|
||||||
|
imu = hardwareMap.get(IMU.class, "imu");
|
||||||
|
|
||||||
|
/* Define how the hub is mounted on the robot to get the correct Yaw, Pitch and Roll values.
|
||||||
|
*
|
||||||
|
* Two input parameters are required to fully specify the Orientation.
|
||||||
|
* The first parameter specifies the direction the printed logo on the Hub is pointing.
|
||||||
|
* The second parameter specifies the direction the USB connector on the Hub is pointing.
|
||||||
|
* All directions are relative to the robot, and left/right is as-viewed from behind the robot.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* The next two lines define Hub orientation.
|
||||||
|
* The Default Orientation (shown) is when a hub is mounted horizontally with the printed logo pointing UP and the USB port pointing FORWARD.
|
||||||
|
*
|
||||||
|
* To Do: EDIT these two lines to match YOUR mounting configuration.
|
||||||
|
*/
|
||||||
|
RevHubOrientationOnRobot.LogoFacingDirection logoDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
||||||
|
RevHubOrientationOnRobot.UsbFacingDirection usbDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
|
||||||
|
|
||||||
|
RevHubOrientationOnRobot orientationOnRobot = new RevHubOrientationOnRobot(logoDirection, usbDirection);
|
||||||
|
|
||||||
|
// Now initialize the IMU with this mounting orientation
|
||||||
|
// Note: if you choose two conflicting directions, this initialization will cause a code exception.
|
||||||
|
imu.initialize(new IMU.Parameters(orientationOnRobot));
|
||||||
|
|
||||||
|
// Loop and update the dashboard
|
||||||
|
while (!isStopRequested()) {
|
||||||
|
|
||||||
|
telemetry.addData("Hub orientation", "Logo=%s USB=%s\n ", logoDirection, usbDirection);
|
||||||
|
|
||||||
|
// Check to see if heading reset is requested
|
||||||
|
if (gamepad1.y) {
|
||||||
|
telemetry.addData("Yaw", "Resetting\n");
|
||||||
|
imu.resetYaw();
|
||||||
|
} else {
|
||||||
|
telemetry.addData("Yaw", "Press Y (triangle) on Gamepad to reset\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Retrieve Rotational Angles and Velocities
|
||||||
|
YawPitchRollAngles orientation = imu.getRobotYawPitchRollAngles();
|
||||||
|
AngularVelocity angularVelocity = imu.getRobotAngularVelocity(AngleUnit.DEGREES);
|
||||||
|
|
||||||
|
telemetry.addData("Yaw (Z)", "%.2f Deg. (Heading)", orientation.getYaw(AngleUnit.DEGREES));
|
||||||
|
telemetry.addData("Pitch (X)", "%.2f Deg.", orientation.getPitch(AngleUnit.DEGREES));
|
||||||
|
telemetry.addData("Roll (Y)", "%.2f Deg.\n", orientation.getRoll(AngleUnit.DEGREES));
|
||||||
|
telemetry.addData("Yaw (Z) velocity", "%.2f Deg/Sec", angularVelocity.zRotationRate);
|
||||||
|
telemetry.addData("Pitch (X) velocity", "%.2f Deg/Sec", angularVelocity.xRotationRate);
|
||||||
|
telemetry.addData("Roll (Y) velocity", "%.2f Deg/Sec", angularVelocity.yRotationRate);
|
||||||
|
telemetry.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,166 @@
|
|||||||
|
/* 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.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||||
|
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.cometbots.MovementLibrary;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 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="CometBots Linear OpMode Demo", group = "[14493] CometBots")
|
||||||
|
public class CometBotsLinearOpMode extends LinearOpMode {
|
||||||
|
|
||||||
|
// Declare OpMode members for each of the 4 motors.
|
||||||
|
private ElapsedTime runtime = new ElapsedTime();
|
||||||
|
private DcMotor rhw = null;
|
||||||
|
private DcMotor rlw = null;
|
||||||
|
private DcMotor lhw = null;
|
||||||
|
private DcMotor llw = null;
|
||||||
|
|
||||||
|
@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.
|
||||||
|
rhw = hardwareMap.get(DcMotor.class, "right hand wheel");
|
||||||
|
rlw = hardwareMap.get(DcMotor.class, "right leg wheel");
|
||||||
|
lhw = hardwareMap.get(DcMotor.class, "left hand wheel");
|
||||||
|
llw = hardwareMap.get(DcMotor.class, "left leg wheel");
|
||||||
|
|
||||||
|
/*
|
||||||
|
Put all motors in an array for easier handling
|
||||||
|
|
||||||
|
NOTE: Placement of motor in array is important especially when dealing with functions
|
||||||
|
that set direction
|
||||||
|
*/
|
||||||
|
DcMotor[] motors = {rhw, rlw, lhw, llw};
|
||||||
|
|
||||||
|
/*
|
||||||
|
Initialize all wheels forward using motors a
|
||||||
|
*/
|
||||||
|
MovementLibrary.setDirectionForward(motors);
|
||||||
|
|
||||||
|
telemetry.addData("Status", "Initialized");
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
runtime.reset();
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
|
||||||
|
// Combine the joystick requests for each axis-motion to determine each wheel's power.
|
||||||
|
// Set up a variable for each drive wheel to save the power level for telemetry.
|
||||||
|
double leftFrontPower = axial + lateral + yaw;
|
||||||
|
double rightFrontPower = axial - lateral - yaw;
|
||||||
|
double leftBackPower = axial - lateral + yaw;
|
||||||
|
double rightBackPower = axial + lateral - yaw;
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
}
|
||||||
|
|
||||||
|
// This is test code:
|
||||||
|
//
|
||||||
|
// Uncomment the following code to test your motor directions.
|
||||||
|
// Each button should make the corresponding motor run FORWARD.
|
||||||
|
// 1) First get all the motors to take to correct positions on the robot
|
||||||
|
// by adjusting your Robot Configuration if necessary.
|
||||||
|
// 2) Then make sure they run in the correct direction by modifying the
|
||||||
|
// the setDirection() calls above.
|
||||||
|
// Once the correct motors move in the correct direction re-comment this code.
|
||||||
|
|
||||||
|
/*
|
||||||
|
leftFrontPower = gamepad1.x ? 1.0 : 0.0; // X gamepad
|
||||||
|
leftBackPower = gamepad1.a ? 1.0 : 0.0; // A gamepad
|
||||||
|
rightFrontPower = gamepad1.y ? 1.0 : 0.0; // Y gamepad
|
||||||
|
rightBackPower = gamepad1.b ? 1.0 : 0.0; // B gamepad
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Send calculated power to wheels
|
||||||
|
lhw.setPower(leftFrontPower);
|
||||||
|
rhw.setPower(rightFrontPower);
|
||||||
|
llw.setPower(leftBackPower);
|
||||||
|
rlw.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();
|
||||||
|
}
|
||||||
|
}}
|
@ -0,0 +1,46 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.openftc.easyopencv.OpenCvCamera;
|
||||||
|
import org.openftc.easyopencv.OpenCvCameraFactory;
|
||||||
|
import org.openftc.easyopencv.OpenCvCameraRotation;
|
||||||
|
|
||||||
|
@Disabled
|
||||||
|
@Autonomous(name="DevApp - OpenCV Demo", group="[14493] CometBots")
|
||||||
|
public class CometBotsOpenCVDemo extends LinearOpMode {
|
||||||
|
|
||||||
|
private OpenCvCamera controlHubCam; // Use OpenCvCamera class from FTC SDK
|
||||||
|
private static final int CAMERA_WIDTH = 1280; // width of wanted camera resolution
|
||||||
|
private static final int CAMERA_HEIGHT = 720; // height of wanted camera resolution
|
||||||
|
|
||||||
|
// Calculate the distance using the formula
|
||||||
|
public static final double objectWidthInRealWorldUnits = 3.75; // Replace with the actual width of the object in real-world units
|
||||||
|
public static final double focalLength = 728; // Replace with the focal length of the camera in pixels
|
||||||
|
|
||||||
|
private void initOpenCV() {
|
||||||
|
|
||||||
|
// Create an instance of the camera
|
||||||
|
int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
|
||||||
|
"cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
|
||||||
|
|
||||||
|
// Use OpenCvCameraFactory class from FTC SDK to create camera instance
|
||||||
|
controlHubCam = OpenCvCameraFactory.getInstance().createWebcam(
|
||||||
|
hardwareMap.get(WebcamName.class, "watch out"), cameraMonitorViewId);
|
||||||
|
|
||||||
|
// controlHubCam.setPipeline(new YellowBlobDetectionPipeline());
|
||||||
|
|
||||||
|
controlHubCam.openCameraDevice();
|
||||||
|
controlHubCam.startStreaming(CAMERA_WIDTH, CAMERA_HEIGHT, OpenCvCameraRotation.UPRIGHT);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,100 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.cometbots.Constants.*;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DistanceSensor;
|
||||||
|
import com.qualcomm.robotcore.hardware.TouchSensor;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.cometbots.MovementLibrary;
|
||||||
|
|
||||||
|
@Disabled
|
||||||
|
@Autonomous(name = "Development Class", group = "[14493] CometBots")
|
||||||
|
public class CometBotsProject extends LinearOpMode {
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
DcMotor rhw = hardwareMap.get(DcMotor.class, "right hand wheel");
|
||||||
|
DcMotor rlw = hardwareMap.get(DcMotor.class, "right leg wheel");
|
||||||
|
DcMotor lhw = hardwareMap.get(DcMotor.class, "left hand wheel");
|
||||||
|
DcMotor llw = hardwareMap.get(DcMotor.class, "left leg wheel");
|
||||||
|
TouchSensor touchSensor = hardwareMap.get(TouchSensor.class, "touchsensor");
|
||||||
|
DistanceSensor distanceSensor = hardwareMap.get(DistanceSensor.class, "distancesensor");
|
||||||
|
ColorSensor colorSensor = hardwareMap.get(ColorSensor.class, "colorsensor");
|
||||||
|
|
||||||
|
/*
|
||||||
|
Put all motors in an array for easier handling
|
||||||
|
|
||||||
|
NOTE: Placement of motor in array is important
|
||||||
|
especially when dealing with functions that
|
||||||
|
set direction
|
||||||
|
*/
|
||||||
|
DcMotor[] motors = {rhw, rlw, lhw, llw};
|
||||||
|
|
||||||
|
/*
|
||||||
|
Initialize all wheels forward using motors array
|
||||||
|
*/
|
||||||
|
// MovementLibrary.setDirectionForward(motors);
|
||||||
|
MovementLibrary.setLeftSideBackward(motors);
|
||||||
|
MovementLibrary.setRightSideForward(motors);
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture color readout from color sensor
|
||||||
|
*/
|
||||||
|
telemetry.addData("Color Sensor [Red]", colorSensor.red());
|
||||||
|
telemetry.addData("Color Sensor [Green]", colorSensor.green());
|
||||||
|
telemetry.addData("Color Sensor [Blue]", colorSensor.blue());
|
||||||
|
telemetry.addData("Color Sensor [Alpha]", colorSensor.alpha());
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture distance readout from distance sensor
|
||||||
|
*/
|
||||||
|
telemetry.addData("Distance Sensor [inches]", distanceSensor.getDistance(DistanceUnit.INCH));
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture state when touch sensor is pressed
|
||||||
|
*/
|
||||||
|
if (touchSensor.isPressed()) {
|
||||||
|
telemetry.speak("Touch sensor is pressed");
|
||||||
|
telemetry.addData("Touch sensor pressed?", touchSensor.isPressed());
|
||||||
|
}
|
||||||
|
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
/*
|
||||||
|
Wait for the driver to hit START in the driver hub
|
||||||
|
*/
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
/*
|
||||||
|
Initialize wheel direction with base speed
|
||||||
|
*/
|
||||||
|
MovementLibrary.setSpeed(motors, CB_BASE_SPEED);
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
Distance traveled in inches
|
||||||
|
*/
|
||||||
|
double distanceInInches = distanceSensor.getDistance(DistanceUnit.INCH);
|
||||||
|
telemetry.addData("Distance traveled (inches)", "%.2f", distanceInInches);
|
||||||
|
|
||||||
|
/*
|
||||||
|
Speed up when going over an object that is blue-ish / green
|
||||||
|
*/
|
||||||
|
if (colorSensor.blue() > 800 && colorSensor.green() > 1100) {
|
||||||
|
telemetry.speak("Green speed boost");
|
||||||
|
MovementLibrary.setSpeed(motors, CB_BASE_SPEED * 2.0);
|
||||||
|
} else {
|
||||||
|
MovementLibrary.setSpeed(motors, CB_BASE_SPEED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,111 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DistanceSensor;
|
||||||
|
import com.qualcomm.robotcore.hardware.TouchSensor;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.cometbots.MovementLibrary;
|
||||||
|
import org.openftc.easyopencv.OpenCvCamera;
|
||||||
|
import org.openftc.easyopencv.OpenCvCameraFactory;
|
||||||
|
import org.openftc.easyopencv.OpenCvCameraRotation;
|
||||||
|
|
||||||
|
@Autonomous(name = "CometBot Sensor Demo", group = "[14493] CometBots")
|
||||||
|
public class CometBotsSensorDemo extends LinearOpMode {
|
||||||
|
|
||||||
|
private OpenCvCamera controlHubCam; // Use OpenCvCamera class from FTC SDK
|
||||||
|
private static final int CAMERA_WIDTH = 1280; // width of wanted camera resolution
|
||||||
|
private static final int CAMERA_HEIGHT = 720; // height of wanted camera resolution
|
||||||
|
|
||||||
|
// Calculate the distance using the formula
|
||||||
|
public static final double objectWidthInRealWorldUnits = 3.75; // Replace with the actual width of the object in real-world units
|
||||||
|
public static final double focalLength = 728; // Replace with the focal length of the camera in pixels
|
||||||
|
|
||||||
|
private DcMotor rhw = null;
|
||||||
|
private DcMotor rlw = null;
|
||||||
|
private DcMotor lhw = null;
|
||||||
|
private DcMotor llw = null;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
// 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.
|
||||||
|
rhw = hardwareMap.get(DcMotor.class, "right hand wheel");
|
||||||
|
rlw = hardwareMap.get(DcMotor.class, "right leg wheel");
|
||||||
|
lhw = hardwareMap.get(DcMotor.class, "left hand wheel");
|
||||||
|
llw = hardwareMap.get(DcMotor.class, "left leg wheel");
|
||||||
|
|
||||||
|
/*
|
||||||
|
Put all motors in an array for easier handling
|
||||||
|
|
||||||
|
NOTE: Placement of motor in array is important especially when dealing with functions
|
||||||
|
that set direction
|
||||||
|
*/
|
||||||
|
DcMotor[] motors = {rhw, rlw, lhw, llw};
|
||||||
|
|
||||||
|
// Create an instance of the camera
|
||||||
|
int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
|
||||||
|
"cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
|
||||||
|
|
||||||
|
// Use OpenCvCameraFactory class from FTC SDK to create camera instance
|
||||||
|
controlHubCam = OpenCvCameraFactory.getInstance().createWebcam(
|
||||||
|
hardwareMap.get(WebcamName.class, "watch out"), cameraMonitorViewId);
|
||||||
|
|
||||||
|
TouchSensor touchSensor = hardwareMap.get(TouchSensor.class, "touchsensor");
|
||||||
|
DistanceSensor distanceSensor = hardwareMap.get(DistanceSensor.class, "distancesensor");
|
||||||
|
ColorSensor colorSensor = hardwareMap.get(ColorSensor.class, "colorsensor");
|
||||||
|
|
||||||
|
controlHubCam.openCameraDevice();
|
||||||
|
controlHubCam.startStreaming(CAMERA_WIDTH, CAMERA_HEIGHT, OpenCvCameraRotation.UPRIGHT);
|
||||||
|
|
||||||
|
FtcDashboard.getInstance().startCameraStream(controlHubCam, 0);
|
||||||
|
|
||||||
|
/*
|
||||||
|
Wait for the driver to hit START in the driver hub
|
||||||
|
*/
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture color readout from color sensor
|
||||||
|
*/
|
||||||
|
telemetry.addData("Color Sensor [Red]", colorSensor.red());
|
||||||
|
telemetry.addData("Color Sensor [Green]", colorSensor.green());
|
||||||
|
telemetry.addData("Color Sensor [Blue]", colorSensor.blue());
|
||||||
|
telemetry.addData("Color Sensor [Alpha]", colorSensor.alpha());
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture distance readout from distance sensor
|
||||||
|
*/
|
||||||
|
telemetry.addData("Distance Sensor [inches]", distanceSensor.getDistance(DistanceUnit.INCH));
|
||||||
|
|
||||||
|
/*
|
||||||
|
Capture state when touch sensor is pressed
|
||||||
|
*/
|
||||||
|
telemetry.addData("Touch sensor pressed?", touchSensor.isPressed());
|
||||||
|
if (touchSensor.isPressed()) {
|
||||||
|
telemetry.speak("Touch sensor is pressed");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (distanceSensor.getDistance(DistanceUnit.INCH) < 3) {
|
||||||
|
telemetry.speak("Warning, unknown object near robot");
|
||||||
|
MovementLibrary.setDirectionRight(motors);
|
||||||
|
MovementLibrary.setSpeed(motors,0.25);
|
||||||
|
sleep(1500);
|
||||||
|
MovementLibrary.setSpeed(motors,0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
Update stats continually
|
||||||
|
*/
|
||||||
|
telemetry.update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,141 @@
|
|||||||
|
/* Copyright (c) 2019 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.LinearOpMode;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
|
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
|
||||||
|
import org.firstinspires.ftc.vision.VisionPortal;
|
||||||
|
import org.firstinspires.ftc.vision.tfod.TfodProcessor;
|
||||||
|
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* This OpMode illustrates the basics of TensorFlow Object Detection, using
|
||||||
|
* the easiest way.
|
||||||
|
*
|
||||||
|
* 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 = "CometBots TensorFlow Demo (HDMI)", group = "[14493] CometBots")
|
||||||
|
public class CometBotsTensorFlowDemo extends LinearOpMode {
|
||||||
|
|
||||||
|
private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The variable to store our instance of the TensorFlow Object Detection processor.
|
||||||
|
*/
|
||||||
|
private TfodProcessor tfod;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The variable to store our instance of the vision portal.
|
||||||
|
*/
|
||||||
|
private VisionPortal visionPortal;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() {
|
||||||
|
|
||||||
|
initTfod();
|
||||||
|
|
||||||
|
// Wait for the DS start button to be touched.
|
||||||
|
telemetry.addData("DS preview on/off", "3 dots, Camera Stream");
|
||||||
|
telemetry.addData(">", "Touch Play to start OpMode");
|
||||||
|
telemetry.update();
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
if (opModeIsActive()) {
|
||||||
|
while (opModeIsActive()) {
|
||||||
|
|
||||||
|
telemetryTfod();
|
||||||
|
|
||||||
|
// Push telemetry to the Driver Station.
|
||||||
|
telemetry.update();
|
||||||
|
|
||||||
|
// Save CPU resources; can resume streaming when needed.
|
||||||
|
if (gamepad1.dpad_down) {
|
||||||
|
visionPortal.stopStreaming();
|
||||||
|
} else if (gamepad1.dpad_up) {
|
||||||
|
visionPortal.resumeStreaming();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
visionPortal.close();
|
||||||
|
|
||||||
|
} // end runOpMode()
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Initialize the TensorFlow Object Detection processor.
|
||||||
|
*/
|
||||||
|
private void initTfod() {
|
||||||
|
|
||||||
|
// Create the TensorFlow processor the easy way.
|
||||||
|
tfod = TfodProcessor.easyCreateWithDefaults();
|
||||||
|
|
||||||
|
// Create the vision portal the easy way.
|
||||||
|
if (USE_WEBCAM) {
|
||||||
|
visionPortal = VisionPortal.easyCreateWithDefaults(
|
||||||
|
hardwareMap.get(WebcamName.class, "watch out"), tfod);
|
||||||
|
} else {
|
||||||
|
visionPortal = VisionPortal.easyCreateWithDefaults(
|
||||||
|
BuiltinCameraDirection.BACK, tfod);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // end method initTfod()
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add telemetry about TensorFlow Object Detection (TFOD) recognitions.
|
||||||
|
*/
|
||||||
|
private void telemetryTfod() {
|
||||||
|
|
||||||
|
List<Recognition> currentRecognitions = tfod.getRecognitions();
|
||||||
|
telemetry.addData("# Objects Detected", currentRecognitions.size());
|
||||||
|
|
||||||
|
// Step through the list of recognitions and display info for each one.
|
||||||
|
for (Recognition recognition : currentRecognitions) {
|
||||||
|
double x = (recognition.getLeft() + recognition.getRight()) / 2 ;
|
||||||
|
double y = (recognition.getTop() + recognition.getBottom()) / 2 ;
|
||||||
|
|
||||||
|
telemetry.addData(""," ");
|
||||||
|
telemetry.addData("Image", "%s (%.0f %% Conf.)", recognition.getLabel(), recognition.getConfidence() * 100);
|
||||||
|
telemetry.addData("- Position", "%.0f / %.0f", x, y);
|
||||||
|
telemetry.addData("- Size", "%.0f x %.0f", recognition.getWidth(), recognition.getHeight());
|
||||||
|
} // end for() loop
|
||||||
|
|
||||||
|
} // end method telemetryTfod()
|
||||||
|
|
||||||
|
} // end class
|
@ -1,45 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
|
||||||
|
|
||||||
public class MovementLibrary {
|
|
||||||
|
|
||||||
|
|
||||||
public static void setDirectionForward (DcMotor rhw, DcMotor rlw, DcMotor lhw, DcMotor llw) {
|
|
||||||
rhw.setDirection(DcMotor.Direction.REVERSE);
|
|
||||||
rlw.setDirection(DcMotor.Direction.FORWARD);
|
|
||||||
lhw.setDirection(DcMotorSimple.Direction.FORWARD);
|
|
||||||
llw.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
}
|
|
||||||
|
|
||||||
public static void setDirectionBackward (DcMotor rhw, DcMotor rlw, DcMotor lhw, DcMotor llw) {
|
|
||||||
rhw.setDirection(DcMotor.Direction.FORWARD);
|
|
||||||
rlw.setDirection(DcMotor.Direction.REVERSE);
|
|
||||||
lhw.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
llw.setDirection(DcMotorSimple.Direction.FORWARD);
|
|
||||||
}
|
|
||||||
|
|
||||||
public static void setDirectionLeft (DcMotor rhw, DcMotor rlw, DcMotor lhw, DcMotor llw) {
|
|
||||||
rhw.setDirection(DcMotor.Direction.REVERSE);
|
|
||||||
rlw.setDirection(DcMotor.Direction.REVERSE);
|
|
||||||
lhw.setDirection(DcMotorSimple.Direction.FORWARD);
|
|
||||||
llw.setDirection(DcMotorSimple.Direction.FORWARD);
|
|
||||||
}
|
|
||||||
|
|
||||||
public static void setDirectionRight (DcMotor rhw, DcMotor rlw, DcMotor lhw, DcMotor llw) {
|
|
||||||
rhw.setDirection(DcMotor.Direction.FORWARD);
|
|
||||||
rlw.setDirection(DcMotor.Direction.FORWARD);
|
|
||||||
lhw.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
llw.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
}
|
|
||||||
|
|
||||||
public static void setSpeed (double speedValue, DcMotor rhw, DcMotor rlw, DcMotor lhw, DcMotor llw) {
|
|
||||||
rhw.setPower(speedValue);
|
|
||||||
rlw.setPower(speedValue);
|
|
||||||
lhw.setPower(speedValue);
|
|
||||||
llw.setPower(speedValue);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
@ -1,87 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode;
|
|
||||||
|
|
||||||
import static java.lang.Math.round;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
import com.qualcomm.robotcore.hardware.AnalogSensor;
|
|
||||||
import com.qualcomm.robotcore.hardware.ColorSensor;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
|
||||||
import com.qualcomm.robotcore.hardware.DistanceSensor;
|
|
||||||
import com.qualcomm.robotcore.hardware.TouchSensor;
|
|
||||||
import org.firstinspires.ftc.teamcode.MovementLibrary;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
|
||||||
|
|
||||||
@Autonomous(name="Name")
|
|
||||||
public class Name extends LinearOpMode {
|
|
||||||
private DcMotor rightHandWheel;
|
|
||||||
private DcMotor rightLegWheel;
|
|
||||||
private DcMotor leftHandWheel;
|
|
||||||
private DcMotor leftLegWheel;
|
|
||||||
private TouchSensor touchSensor;
|
|
||||||
private DistanceSensor distanceSensor;
|
|
||||||
private ColorSensor colorSensor;
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
rightHandWheel = hardwareMap.get(DcMotor.class,"right hand wheel");
|
|
||||||
rightLegWheel = hardwareMap.get(DcMotor.class,"right leg wheel");
|
|
||||||
leftHandWheel = hardwareMap.get(DcMotor.class, "left hand wheel");
|
|
||||||
leftLegWheel = hardwareMap.get(DcMotor.class, "left leg wheel");
|
|
||||||
touchSensor = hardwareMap.get(TouchSensor.class, "touchsensor");
|
|
||||||
distanceSensor = hardwareMap.get(DistanceSensor.class , "distancesensor");
|
|
||||||
colorSensor = hardwareMap.get(ColorSensor.class, "colorsensor");
|
|
||||||
|
|
||||||
MovementLibrary.setDirectionForward(rightHandWheel,rightLegWheel,leftHandWheel,leftLegWheel);
|
|
||||||
MovementLibrary.setSpeed(0.2,rightHandWheel,rightLegWheel,leftHandWheel,leftLegWheel);
|
|
||||||
|
|
||||||
// Wait for the game to start (driver presses PLAY)
|
|
||||||
waitForStart();
|
|
||||||
|
|
||||||
while(opModeIsActive()){
|
|
||||||
|
|
||||||
/* telemetry.speak( "Oh see, you see" +
|
|
||||||
"By the dusk's late light" +
|
|
||||||
"What so proudly we rained" +
|
|
||||||
"At the twilight's last gleaming?" +
|
|
||||||
"Whose broad stripes and dark stars" +
|
|
||||||
"Through the perilous fight" +
|
|
||||||
"Under the ramparts we watched" +
|
|
||||||
"Were so gallantly, no, streaming?" +
|
|
||||||
"And the rockets' red glare" +
|
|
||||||
"The bombs contracting in air" +
|
|
||||||
"Gave proof through the night" +
|
|
||||||
"That our flag was not there" +
|
|
||||||
"O say, that star-spangled banner doesn't wave" +
|
|
||||||
"Over the land of the enslaved and the home of the cowardly");*/
|
|
||||||
|
|
||||||
MovementLibrary.setSpeed(0.2,rightHandWheel,rightLegWheel,leftHandWheel,leftLegWheel);
|
|
||||||
|
|
||||||
if(touchSensor.isPressed()) {
|
|
||||||
telemetry.speak("Ouchie that hurt me and my feelings");
|
|
||||||
telemetry.addData("was i triggered", touchSensor.isPressed());
|
|
||||||
}
|
|
||||||
|
|
||||||
double nicerValue = distanceSensor.getDistance(DistanceUnit.INCH);
|
|
||||||
|
|
||||||
telemetry.addData("you are this far (in inches) --> ", "%.2f", nicerValue);
|
|
||||||
telemetry.addData("Red: ", colorSensor.red());
|
|
||||||
telemetry.addData("Green: ", colorSensor.green());
|
|
||||||
telemetry.addData("Blue: ", colorSensor.blue());
|
|
||||||
|
|
||||||
if(colorSensor.green() > 1100 && colorSensor.blue() > 1000) {
|
|
||||||
MovementLibrary.setSpeed(0.4,rightHandWheel,rightLegWheel,leftHandWheel,leftLegWheel);
|
|
||||||
} else {
|
|
||||||
MovementLibrary.setSpeed(0.2,rightHandWheel,rightLegWheel,leftHandWheel,leftLegWheel);
|
|
||||||
};
|
|
||||||
|
|
||||||
telemetry.update();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
@ -0,0 +1,7 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.cometbots;
|
||||||
|
|
||||||
|
public class Constants {
|
||||||
|
|
||||||
|
public static double CB_BASE_SPEED = 0.2;
|
||||||
|
|
||||||
|
}
|
@ -0,0 +1,58 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.cometbots;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
|
||||||
|
public class MovementLibrary {
|
||||||
|
|
||||||
|
public static void setDirectionForward(DcMotor[] motors) {
|
||||||
|
setLeftSideForward(motors);
|
||||||
|
setRightSideForward(motors);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setLeftSideForward(DcMotor[] motors) {
|
||||||
|
motors[2].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
motors[3].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setRightSideForward(DcMotor[] motors) {
|
||||||
|
motors[0].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
motors[1].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setLeftSideBackward(DcMotor[] motors) {
|
||||||
|
motors[2].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
motors[3].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setRightSideBackward(DcMotor[] motors) {
|
||||||
|
motors[0].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
motors[1].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public static void setDirectionBackward(DcMotor[] motors) {
|
||||||
|
setLeftSideBackward(motors);
|
||||||
|
setRightSideBackward(motors);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setSpeed(DcMotor[] motors, double speedValue) {
|
||||||
|
for (DcMotor motor : motors) {
|
||||||
|
motor.setPower(speedValue);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setDirectionLeft(DcMotor[] motors) {
|
||||||
|
motors[0].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
motors[1].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
motors[2].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
motors[3].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static void setDirectionRight(DcMotor[] motors) {
|
||||||
|
motors[0].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
motors[1].setDirection(DcMotor.Direction.FORWARD);
|
||||||
|
motors[2].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
motors[3].setDirection(DcMotor.Direction.REVERSE);
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,4 @@
|
|||||||
|
https://www.youtube.com/watch?v=aeMWWvteF2U
|
||||||
|
|
||||||
|
https://www.youtube.com/watch?v=1xdo8QP6_mI
|
||||||
|
|
@ -1,6 +1,7 @@
|
|||||||
repositories {
|
repositories {
|
||||||
mavenCentral()
|
mavenCentral()
|
||||||
google() // Needed for androidx
|
google() // Needed for androidx
|
||||||
|
maven { url = 'https://maven.brott.dev/' }
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
@ -17,5 +18,6 @@ dependencies {
|
|||||||
implementation 'org.tensorflow:tensorflow-lite-task-vision:0.4.3'
|
implementation 'org.tensorflow:tensorflow-lite-task-vision:0.4.3'
|
||||||
runtimeOnly 'org.tensorflow:tensorflow-lite:2.12.0'
|
runtimeOnly 'org.tensorflow:tensorflow-lite:2.12.0'
|
||||||
implementation 'androidx.appcompat:appcompat:1.2.0'
|
implementation 'androidx.appcompat:appcompat:1.2.0'
|
||||||
|
implementation 'com.acmerobotics.dashboard:dashboard:0.4.15' // FTC Dashboard
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user