Merge branch 'master' into danielv5
This commit is contained in:
@@ -1,8 +1,8 @@
|
|||||||
<?xml version="1.0" encoding="utf-8"?>
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
|
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
|
||||||
xmlns:tools="http://schemas.android.com/tools"
|
xmlns:tools="http://schemas.android.com/tools"
|
||||||
android:versionCode="60"
|
android:versionCode="61"
|
||||||
android:versionName="11.0">
|
android:versionName="11.1">
|
||||||
|
|
||||||
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
|
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
|
||||||
|
|
||||||
|
|||||||
@@ -92,24 +92,22 @@ public class ConceptAprilTag extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
while (opModeIsActive()) {
|
|
||||||
|
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
}
|
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -88,24 +88,22 @@ public class ConceptAprilTagEasy extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
while (opModeIsActive()) {
|
|
||||||
|
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
}
|
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -81,27 +81,25 @@ public class ConceptAprilTagSwitchableCameras extends LinearOpMode {
|
|||||||
telemetry.update();
|
telemetry.update();
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
if (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
while (opModeIsActive()) {
|
|
||||||
|
|
||||||
telemetryCameraSwitching();
|
telemetryCameraSwitching();
|
||||||
telemetryAprilTag();
|
telemetryAprilTag();
|
||||||
|
|
||||||
// Push telemetry to the Driver Station.
|
// Push telemetry to the Driver Station.
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
|
|
||||||
// Save CPU resources; can resume streaming when needed.
|
// Save CPU resources; can resume streaming when needed.
|
||||||
if (gamepad1.dpad_down) {
|
if (gamepad1.dpad_down) {
|
||||||
visionPortal.stopStreaming();
|
visionPortal.stopStreaming();
|
||||||
} else if (gamepad1.dpad_up) {
|
} else if (gamepad1.dpad_up) {
|
||||||
visionPortal.resumeStreaming();
|
visionPortal.resumeStreaming();
|
||||||
}
|
|
||||||
|
|
||||||
doCameraSwitching();
|
|
||||||
|
|
||||||
// Share the CPU.
|
|
||||||
sleep(20);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
doCameraSwitching();
|
||||||
|
|
||||||
|
// Share the CPU.
|
||||||
|
sleep(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Save more CPU resources when camera is no longer needed.
|
// Save more CPU resources when camera is no longer needed.
|
||||||
|
|||||||
@@ -83,6 +83,22 @@ public class ConceptGamepadEdgeDetection extends LinearOpMode {
|
|||||||
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
|
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
|
||||||
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
|
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
|
||||||
|
|
||||||
|
// Add an empty line to separate the buttons in telemetry
|
||||||
|
telemetry.addLine();
|
||||||
|
|
||||||
|
// Add the status of the Gamepad 1 Left trigger
|
||||||
|
telemetry.addData("Gamepad 1 Left Trigger Pressed", gamepad1.leftTriggerWasPressed());
|
||||||
|
telemetry.addData("Gamepad 1 Left Trigger Released", gamepad1.leftTriggerWasReleased());
|
||||||
|
telemetry.addData("Gamepad 1 Left Trigger Status", gamepad1.left_trigger_pressed);
|
||||||
|
|
||||||
|
// Add an empty line to separate the buttons in telemetry
|
||||||
|
telemetry.addLine();
|
||||||
|
|
||||||
|
// Add the status of the Gamepad 1 Right trigger
|
||||||
|
telemetry.addData("Gamepad 1 Right Trigger Pressed", gamepad1.rightTriggerWasPressed());
|
||||||
|
telemetry.addData("Gamepad 1 Right Trigger Released", gamepad1.rightTriggerWasReleased());
|
||||||
|
telemetry.addData("Gamepad 1 Right Trigger Status", gamepad1.right_trigger_pressed);
|
||||||
|
|
||||||
// Add a note that the telemetry is only updated every 2 seconds
|
// Add a note that the telemetry is only updated every 2 seconds
|
||||||
telemetry.addLine("\nTelemetry is updated every 2 seconds.");
|
telemetry.addLine("\nTelemetry is updated every 2 seconds.");
|
||||||
|
|
||||||
|
|||||||
@@ -27,7 +27,7 @@
|
|||||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|||||||
@@ -27,7 +27,7 @@
|
|||||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|||||||
15
README.md
15
README.md
@@ -59,6 +59,21 @@ The readme.md file located in the [/TeamCode/src/main/java/org/firstinspires/ftc
|
|||||||
|
|
||||||
# Release Information
|
# Release Information
|
||||||
|
|
||||||
|
## Version 11.1 (20251231-104637)
|
||||||
|
|
||||||
|
### Enhancements
|
||||||
|
|
||||||
|
* Gamepad triggers can now be accessed as booleans and have edge detection supported.
|
||||||
|
* GoBildaPinpointDriver now supports Pinpoint v2 functionality
|
||||||
|
* Adds webcam calibrations for goBILDA's USB camera.
|
||||||
|
|
||||||
|
### Bug Fixes
|
||||||
|
* Fixes issue [1654](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1654) in GoBildaPinpointDriver that caused error if resolution was set in other than MM
|
||||||
|
* Fixes issue [1628](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1628) Blocks editor displays incorrect Java code for gamepad edge detection blocks.
|
||||||
|
* Fixes possible race condition issue [1884](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1884) on Driver Station startup when Driver Station name doesn't match the Robot Controller name.
|
||||||
|
* Fixes issue [1863](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/1863) - Incorrect package paths in samples.
|
||||||
|
* Fixes an issue where an OnBotJava filename that begins with a lowercase character would fail to properly rename the file if the user tried to rename it so that it begins with an uppercase character.
|
||||||
|
|
||||||
## Version 11.0 (20250827-105138)
|
## Version 11.0 (20250827-105138)
|
||||||
|
|
||||||
### Enhancements
|
### Enhancements
|
||||||
|
|||||||
@@ -12,8 +12,25 @@
|
|||||||
// Custom definitions may go here
|
// Custom definitions may go here
|
||||||
|
|
||||||
// Include common definitions from above.
|
// Include common definitions from above.
|
||||||
|
|
||||||
|
buildscript {
|
||||||
|
repositories {
|
||||||
|
mavenCentral()
|
||||||
|
maven {
|
||||||
|
url "https://repo.dairy.foundation/releases"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
dependencies {
|
||||||
|
classpath "dev.frozenmilk:Load:0.2.4"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
apply from: '../build.common.gradle'
|
apply from: '../build.common.gradle'
|
||||||
apply from: '../build.dependencies.gradle'
|
apply from: '../build.dependencies.gradle'
|
||||||
|
// there should be 2 or 3 more lines that start with 'apply plugin:' here
|
||||||
|
apply plugin: 'dev.frozenmilk.sinister.sloth.load'
|
||||||
|
|
||||||
|
|
||||||
android {
|
android {
|
||||||
namespace = 'org.firstinspires.ftc.teamcode'
|
namespace = 'org.firstinspires.ftc.teamcode'
|
||||||
@@ -28,14 +45,32 @@ repositories {
|
|||||||
maven {
|
maven {
|
||||||
url = 'https://maven.brott.dev/'
|
url = 'https://maven.brott.dev/'
|
||||||
}
|
}
|
||||||
|
// Dairy releases repository
|
||||||
|
maven {
|
||||||
|
url = "https://repo.dairy.foundation/releases"
|
||||||
|
}
|
||||||
|
// Dairy snapshots repository
|
||||||
|
maven {
|
||||||
|
url = "https://repo.dairy.foundation/snapshots"
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation project(':FtcRobotController')
|
implementation project(':FtcRobotController')
|
||||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25"
|
implementation("dev.frozenmilk.sinister:Sloth:0.2.4")
|
||||||
implementation "com.acmerobotics.roadrunner:core:1.0.1"
|
|
||||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1"
|
|
||||||
implementation "com.acmerobotics.dashboard:dashboard:0.5.1"
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // core
|
implementation 'org.ftclib.ftclib:core:2.1.1' // core
|
||||||
|
implementation("com.acmerobotics.roadrunner:ftc:0.1.25") {
|
||||||
|
exclude group: "com.acmerobotics.dashboard"
|
||||||
|
}
|
||||||
|
implementation("com.acmerobotics.roadrunner:actions:1.0.1") {
|
||||||
|
exclude group: "com.acmerobotics.dashboard"
|
||||||
|
}
|
||||||
|
implementation("com.acmerobotics.roadrunner:core:1.0.1") {
|
||||||
|
exclude group: "com.acmerobotics.dashboard"
|
||||||
|
}
|
||||||
|
|
||||||
|
implementation("com.acmerobotics.slothboard:dashboard:0.2.4+0.5.1") //Slothdashboard
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -6,6 +6,11 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
public class Color {
|
public class Color {
|
||||||
public static boolean redAlliance = true;
|
public static boolean redAlliance = true;
|
||||||
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
|
public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5;
|
||||||
|
public static double LightGreen = 0.5;
|
||||||
|
public static double LightPurple = 0.715;
|
||||||
|
public static double LightOrange = 0.33;
|
||||||
|
public static double LightRed = 0.28;
|
||||||
|
public static double LightBlue = 0.6;
|
||||||
|
|
||||||
public static double colorFilterAlpha = 1;
|
public static double colorFilterAlpha = 1;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,10 +1,19 @@
|
|||||||
package org.firstinspires.ftc.teamcode.constants;
|
package org.firstinspires.ftc.teamcode.constants;
|
||||||
|
|
||||||
public class Types {
|
public class StateEnums {
|
||||||
public enum Motif {
|
public enum Motif {
|
||||||
NONE,
|
NONE,
|
||||||
GPP, // Green, Purple, Purple
|
GPP, // Green, Purple, Purple
|
||||||
PGP, // Purple, Green, Purple
|
PGP, // Purple, Green, Purple
|
||||||
PPG // Purple, Purple, Green
|
PPG // Purple, Purple, Green
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public enum LightState {
|
||||||
|
BALL_COUNT,
|
||||||
|
BALL_COLOR,
|
||||||
|
GOAL_LOCK,
|
||||||
|
MANUAL,
|
||||||
|
DISABLED,
|
||||||
|
OFF
|
||||||
|
}
|
||||||
}
|
}
|
||||||
@@ -16,9 +16,12 @@ import com.qualcomm.hardware.lynx.LynxModule;
|
|||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Drivetrain;
|
import org.firstinspires.ftc.teamcode.utils.Drivetrain;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||||
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
|
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||||
@@ -48,6 +51,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
boolean fixedTurret = false;
|
boolean fixedTurret = false;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
|
Light light;
|
||||||
Servos servo;
|
Servos servo;
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
@@ -65,7 +69,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
double headingOffset = 0.0;
|
double headingOffset = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
|
|
||||||
boolean autoSpintake = false;
|
boolean autoSpintake = false;
|
||||||
boolean enableSpindexerManager = true;
|
boolean enableSpindexerManager = true;
|
||||||
|
|
||||||
@@ -102,6 +105,11 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
tController.setTolerance(0.001);
|
tController.setTolerance(0.001);
|
||||||
|
|
||||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||||
|
|
||||||
|
light = Light.getInstance();
|
||||||
|
light.init(robot.light, spindexer, turret);
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.MANUAL);
|
||||||
limelightUsed = true;
|
limelightUsed = true;
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
robot.light.setPosition(1);
|
||||||
@@ -109,11 +117,18 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
robot.limelight.pipelineSwitch(4);
|
robot.limelight.pipelineSwitch(4);
|
||||||
|
light.setManualLightColor(Color.LightRed);
|
||||||
} else {
|
} else {
|
||||||
robot.limelight.pipelineSwitch(2);
|
robot.limelight.pipelineSwitch(2);
|
||||||
|
light.setManualLightColor(Color.LightBlue);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
light.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
limelightUsed = true;
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
@@ -124,9 +139,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//TELE.addData("Is limelight on?", robot.limelight.getStatus());
|
//TELE.addData("Is limelight on?", robot.limelight.getStatus());
|
||||||
|
|
||||||
// LIGHT COLORS
|
|
||||||
spindexer.ballCounterLight();
|
|
||||||
|
|
||||||
//DRIVETRAIN:
|
//DRIVETRAIN:
|
||||||
|
|
||||||
drivetrain.drive(
|
drivetrain.drive(
|
||||||
@@ -137,9 +149,17 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
);
|
);
|
||||||
|
|
||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
|
|
||||||
shootAll = false;
|
shootAll = false;
|
||||||
servo.setTransferPos(transferServo_out);
|
servo.setTransferPos(transferServo_out);
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||||
|
|
||||||
|
} else if (gamepad2.triangle){
|
||||||
|
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
light.setState(StateEnums.LightState.GOAL_LOCK);
|
||||||
}
|
}
|
||||||
|
|
||||||
//TURRET TRACKING
|
//TURRET TRACKING
|
||||||
@@ -230,6 +250,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (enableSpindexerManager) {
|
if (enableSpindexerManager) {
|
||||||
//if (!shootAll) {
|
//if (!shootAll) {
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
@@ -321,16 +343,16 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
//
|
//
|
||||||
// TELE.addData("shootall commanded", shootAll);
|
// TELE.addData("shootall commanded", shootAll);
|
||||||
// Targeting Debug
|
// Targeting Debug
|
||||||
// TELE.addData("robotX", robotX);
|
TELE.addData("robotX", robotX);
|
||||||
// TELE.addData("robotY", robotY);
|
TELE.addData("robotY", robotY);
|
||||||
// TELE.addData("robotInchesX", targeting.robotInchesX);
|
TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||||
// TELE.addData( "robotInchesY", targeting.robotInchesY);
|
TELE.addData("robotInchesY", targeting.robotInchesY);
|
||||||
// TELE.addData("Targeting Interpolate", turretInterpolate);
|
TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||||
// TELE.addData("Targeting GridX", targeting.robotGridX);
|
TELE.addData("Targeting GridX", targeting.robotGridX);
|
||||||
// TELE.addData("Targeting GridY", targeting.robotGridY);
|
TELE.addData("Targeting GridY", targeting.robotGridY);
|
||||||
// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||||
// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||||
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||||
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
||||||
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
||||||
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
||||||
@@ -338,6 +360,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
|
light.update();
|
||||||
|
|
||||||
ticker++;
|
ticker++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,108 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.StateEnums.LightState;
|
||||||
|
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public final class Light {
|
||||||
|
|
||||||
|
private static Light instance;
|
||||||
|
public static double ballColorCycleTime = 1000; //in ms
|
||||||
|
public static double restingTime = 150; //in ms
|
||||||
|
|
||||||
|
private Servo lightServo;
|
||||||
|
private LightState state = LightState.DISABLED;
|
||||||
|
|
||||||
|
// References to other systems (NOT static)
|
||||||
|
private Spindexer spindexer;
|
||||||
|
private Turret turret;
|
||||||
|
private double manualLightColor = Color.Light0;
|
||||||
|
|
||||||
|
private double lightColor = Color.Light0;
|
||||||
|
private double previousLightColor = lightColor;
|
||||||
|
|
||||||
|
private Light() {
|
||||||
|
}
|
||||||
|
|
||||||
|
public static synchronized Light getInstance() {
|
||||||
|
if (instance == null) {
|
||||||
|
instance = new Light();
|
||||||
|
}
|
||||||
|
return instance;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Call once in OpMode init()
|
||||||
|
public void init(
|
||||||
|
Servo servo,
|
||||||
|
Spindexer spin,
|
||||||
|
Turret turr
|
||||||
|
) {
|
||||||
|
this.lightServo = servo;
|
||||||
|
this.spindexer = spin;
|
||||||
|
this.turret = turr;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setManualLightColor(double value) {
|
||||||
|
this.manualLightColor = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void setState(LightState newState) {
|
||||||
|
state = newState;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update() {
|
||||||
|
if (lightServo == null) return;
|
||||||
|
|
||||||
|
switch (state) {
|
||||||
|
|
||||||
|
case BALL_COUNT:
|
||||||
|
lightColor = spindexer.ballCounterLight();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BALL_COLOR:
|
||||||
|
|
||||||
|
if ((System.currentTimeMillis() % ballColorCycleTime) < ((ballColorCycleTime / 3) - restingTime)) {
|
||||||
|
lightColor = spindexer.getRearCenterLight();
|
||||||
|
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime / 3)) {
|
||||||
|
lightColor = 0;
|
||||||
|
} else if ((System.currentTimeMillis() % ballColorCycleTime) < ((2 * ballColorCycleTime / 3) - restingTime)) {
|
||||||
|
lightColor = spindexer.getDriverLight();
|
||||||
|
|
||||||
|
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (2 * ballColorCycleTime / 3)) {
|
||||||
|
lightColor = 0;
|
||||||
|
} else if ((System.currentTimeMillis() % ballColorCycleTime) < (ballColorCycleTime - restingTime)) {
|
||||||
|
lightColor = spindexer.getPassengerLight();
|
||||||
|
|
||||||
|
} else {
|
||||||
|
lightColor = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GOAL_LOCK:
|
||||||
|
lightColor = turret.getLightColor();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MANUAL:
|
||||||
|
lightColor = manualLightColor;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case DISABLED:
|
||||||
|
break;
|
||||||
|
|
||||||
|
case OFF:
|
||||||
|
lightColor = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (lightColor != previousLightColor) {
|
||||||
|
lightServo.setPosition(lightColor);
|
||||||
|
}
|
||||||
|
|
||||||
|
previousLightColor = lightColor;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -22,9 +22,11 @@ import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
|||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.constants.Types;
|
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
|
||||||
|
import java.util.Objects;
|
||||||
|
|
||||||
public class Spindexer {
|
public class Spindexer {
|
||||||
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
@@ -50,7 +52,7 @@ public class Spindexer {
|
|||||||
private double prevPos = 0.0;
|
private double prevPos = 0.0;
|
||||||
public double spindexerPosOffset = 0.00;
|
public double spindexerPosOffset = 0.00;
|
||||||
public static int shootWaitMax = 4;
|
public static int shootWaitMax = 4;
|
||||||
public Types.Motif desiredMotif = Types.Motif.NONE;
|
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
|
||||||
// For Use
|
// For Use
|
||||||
enum RotatedBallPositionNames {
|
enum RotatedBallPositionNames {
|
||||||
REARCENTER,
|
REARCENTER,
|
||||||
@@ -284,35 +286,65 @@ public class Spindexer {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private double prevLight = 0.0;
|
public double getRearCenterLight() {
|
||||||
public void ballCounterLight(){
|
BallColor color = GetRearCenterColor();
|
||||||
|
if (Objects.equals(color, BallColor.GREEN)) {
|
||||||
|
return LightGreen;
|
||||||
|
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
||||||
|
return LightPurple;
|
||||||
|
} else {
|
||||||
|
return LightOrange;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public double getDriverLight() {
|
||||||
|
BallColor color = GetFrontDriverColor();
|
||||||
|
if (Objects.equals(color, BallColor.GREEN)) {
|
||||||
|
return LightGreen;
|
||||||
|
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
||||||
|
return LightPurple;
|
||||||
|
} else {
|
||||||
|
return LightOrange;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getPassengerLight() {
|
||||||
|
BallColor color = GetFrontPassengerColor();
|
||||||
|
if (Objects.equals(color, BallColor.GREEN)) {
|
||||||
|
return LightGreen;
|
||||||
|
} else if (Objects.equals(color, BallColor.PURPLE)) {
|
||||||
|
return LightPurple;
|
||||||
|
} else {
|
||||||
|
return LightOrange;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
public double ballCounterLight() {
|
||||||
int counter = 0;
|
int counter = 0;
|
||||||
if (!ballPositions[0].isEmpty){
|
if (!ballPositions[0].isEmpty) {
|
||||||
counter++;
|
counter++;
|
||||||
}
|
}
|
||||||
if (!ballPositions[1].isEmpty){
|
if (!ballPositions[1].isEmpty) {
|
||||||
counter++;
|
counter++;
|
||||||
}
|
}
|
||||||
if (!ballPositions[2].isEmpty){
|
if (!ballPositions[2].isEmpty) {
|
||||||
counter++;
|
counter++;
|
||||||
}
|
}
|
||||||
|
|
||||||
double light;
|
if (counter == 3) {
|
||||||
if (counter == 3){
|
return Light3;
|
||||||
light = Light3;
|
} else if (counter == 2) {
|
||||||
} else if (counter == 2){
|
return Light2;
|
||||||
light = Light2;
|
} else if (counter == 1) {
|
||||||
} else if (counter == 1){
|
return Light1;
|
||||||
light = Light1;
|
|
||||||
} else {
|
} else {
|
||||||
light = Light0;
|
return Light0;
|
||||||
}
|
}
|
||||||
if (light != prevLight){
|
|
||||||
robot.light.setPosition(light);
|
|
||||||
}
|
|
||||||
prevLight = light;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public boolean slotIsEmpty(int slot){
|
public boolean slotIsEmpty(int slot){
|
||||||
return !ballPositions[slot].isEmpty;
|
return !ballPositions[slot].isEmpty;
|
||||||
}
|
}
|
||||||
@@ -531,7 +563,7 @@ public class Spindexer {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
public void setDesiredMotif (Types.Motif newMotif) {
|
public void setDesiredMotif (StateEnums.Motif newMotif) {
|
||||||
desiredMotif = newMotif;
|
desiredMotif = newMotif;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -9,11 +9,11 @@ import com.arcrobotics.ftclib.controller.PIDController;
|
|||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||||
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@@ -53,6 +53,7 @@ public class Turret {
|
|||||||
private int obeliskID = 0;
|
private int obeliskID = 0;
|
||||||
private double offset = 0.0;
|
private double offset = 0.0;
|
||||||
private double currentTrackOffset = 0.0;
|
private double currentTrackOffset = 0.0;
|
||||||
|
private double lightColor = Color.LightRed;
|
||||||
private int currentTrackCount = 0;
|
private int currentTrackCount = 0;
|
||||||
private double permanentOffset = 0.0;
|
private double permanentOffset = 0.0;
|
||||||
private PIDController bearingPID;
|
private PIDController bearingPID;
|
||||||
@@ -67,6 +68,10 @@ public class Turret {
|
|||||||
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
|
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public double getLightColor() {
|
||||||
|
return lightColor;
|
||||||
|
}
|
||||||
|
|
||||||
public void zeroTurretEncoder() {
|
public void zeroTurretEncoder() {
|
||||||
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
@@ -161,11 +166,17 @@ public class Turret {
|
|||||||
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
||||||
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
||||||
final double DRIVE_POWER_REDUCTION = 2.0;
|
final double DRIVE_POWER_REDUCTION = 2.0;
|
||||||
|
final double COLOR_OK_TOLERANCE = 2.5;
|
||||||
|
|
||||||
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
||||||
bearingAligned = true;
|
bearingAligned = true;
|
||||||
} else {
|
lightColor = Color.LightBlue;
|
||||||
|
} else if (abs(targetTx) < COLOR_OK_TOLERANCE) {
|
||||||
bearingAligned = false;
|
bearingAligned = false;
|
||||||
|
lightColor = Color.LightPurple;
|
||||||
|
} else {
|
||||||
|
bearingAligned = false;
|
||||||
|
lightColor = Color.LightOrange;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Only with valid data and if too far off target
|
// Only with valid data and if too far off target
|
||||||
@@ -254,6 +265,7 @@ public class Turret {
|
|||||||
// if (currentTrackCount > 20) {
|
// if (currentTrackCount > 20) {
|
||||||
// offset = currentTrackOffset;
|
// offset = currentTrackOffset;
|
||||||
// }
|
// }
|
||||||
|
lightColor = Color.LightRed;
|
||||||
currentTrackOffset = 0.0;
|
currentTrackOffset = 0.0;
|
||||||
currentTrackCount = 0;
|
currentTrackCount = 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -6,30 +6,26 @@ repositories {
|
|||||||
maven { url = 'https://maven.brott.dev/' } //RR
|
maven { url = 'https://maven.brott.dev/' } //RR
|
||||||
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
||||||
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
implementation 'org.firstinspires.ftc:Inspection:11.0.0'
|
implementation 'org.firstinspires.ftc:Inspection:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:Blocks:11.0.0'
|
implementation 'org.firstinspires.ftc:Blocks:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:RobotCore:11.0.0'
|
//noinspection Aligned16KB
|
||||||
implementation 'org.firstinspires.ftc:RobotServer:11.0.0'
|
implementation 'org.firstinspires.ftc:RobotCore:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:OnBotJava:11.0.0'
|
implementation 'org.firstinspires.ftc:RobotServer:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:Hardware:11.0.0'
|
implementation 'org.firstinspires.ftc:OnBotJava:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:FtcCommon:11.0.0'
|
implementation 'org.firstinspires.ftc:Hardware:11.1.0'
|
||||||
implementation 'org.firstinspires.ftc:Vision:11.0.0'
|
implementation 'org.firstinspires.ftc:FtcCommon:11.1.0'
|
||||||
|
implementation 'org.firstinspires.ftc:Vision:11.1.0'
|
||||||
implementation 'androidx.appcompat:appcompat:1.2.0'
|
implementation 'androidx.appcompat:appcompat:1.2.0'
|
||||||
|
|
||||||
|
|
||||||
|
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
||||||
implementation 'com.pedropathing:ftc:2.0.1' //PedroCore
|
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
||||||
implementation 'com.pedropathing:telemetry:0.0.6' //PedroTele
|
|
||||||
|
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR
|
|
||||||
implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR
|
|
||||||
implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR
|
|
||||||
implementation "com.acmerobotics.dashboard:dashboard:0.5.1" //FTC Dash
|
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
@@ -40,11 +36,5 @@ dependencies {
|
|||||||
implementation("page.j5155.AdvantageScope:lite:v26.0.0") //AS
|
implementation("page.j5155.AdvantageScope:lite:v26.0.0") //AS
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user