diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 00000000..d7be9dd1 --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,47 @@ +name: CI + +on: + # Update on pushes to main + push: + branches: [ "main" ] + + pull_request: + + # Allow running workflow manually + workflow_dispatch: + +jobs: + lint: + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v3 + + - name: Setup JDK 17 + uses: actions/setup-java@v4 + with: + java-version: 17 + distribution: 'temurin' + cache: 'gradle' + + - name: Lint project + run: | + chmod +x ./gradlew + ./gradlew lintKotlin + build: + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v3 + + - name: Setup JDK 17 + uses: actions/setup-java@v4 + with: + java-version: 17 + distribution: 'temurin' + cache: 'gradle' + + - name: Build project + run: | + chmod +x ./gradlew + ./gradlew build diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml index 3db283e1..37857be6 100644 --- a/.github/workflows/docs.yml +++ b/.github/workflows/docs.yml @@ -30,10 +30,10 @@ jobs: - name: Checkout uses: actions/checkout@v3 - - name: Setup JDK 11 - uses: actions/setup-java@v3 + - name: Setup JDK 17 + uses: actions/setup-java@v4 with: - java-version: 11 + java-version: 17 distribution: 'temurin' cache: 'gradle' diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml deleted file mode 100644 index 5bb87df1..00000000 --- a/.github/workflows/lint.yml +++ /dev/null @@ -1,30 +0,0 @@ -name: Lint - -on: - # Update on pushes to main - push: - branches: [ "main" ] - - pull_request: - - # Allow running workflow manually - workflow_dispatch: - -jobs: - lint: - runs-on: ubuntu-latest - steps: - - name: Checkout - uses: actions/checkout@v3 - - - name: Setup JDK 11 - uses: actions/setup-java@v3 - with: - java-version: 11 - distribution: 'temurin' - cache: 'gradle' - - - name: Lint project - run: | - chmod +x ./gradlew - ./gradlew lintKotlin diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/API.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/API.kt index 2930f8d4..05c8c54c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/API.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/API.kt @@ -23,7 +23,7 @@ abstract class API { @Deprecated( message = "Accessing the hardwareMap indirectly is not supported.", replaceWith = ReplaceWith("this.opMode.hardwareMap"), - level = DeprecationLevel.WARNING, + level = DeprecationLevel.ERROR, ) protected val hardwareMap: HardwareMap get() = this.opMode.hardwareMap diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/Box.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/Box.kt index ae2d5dbf..24f79fb4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/Box.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/Box.kt @@ -7,6 +7,10 @@ import org.firstinspires.ftc.teamcode.utils.opModeSleep /** * An API for controlling the Box on the robot. */ +@Deprecated( + message = "The Box hardware component has been removed.", + level = DeprecationLevel.WARNING, +) object Box : API() { private lateinit var box: Servo private lateinit var grip: Servo @@ -14,8 +18,8 @@ object Box : API() { override fun init(opMode: OpMode) { super.init(opMode) - this.box = this.hardwareMap.get(Servo::class.java, "box") - this.grip = this.hardwareMap.get(Servo::class.java, "grip") + this.box = this.opMode.hardwareMap.get(Servo::class.java, "box") + this.grip = this.opMode.hardwareMap.get(Servo::class.java, "grip") // Close grip at the beginning. this.gripOut() diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/DemoQuadWheels.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/DemoQuadWheels.kt index 7817816a..83ce2ae2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/DemoQuadWheels.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/DemoQuadWheels.kt @@ -33,10 +33,10 @@ object DemoQuadWheels : API() { // You must call super.init(opMode), or the API will not initialize correctly. super.init(opMode) - this.fl = this.hardwareMap.get(DcMotor::class.java, "fl") - this.fr = this.hardwareMap.get(DcMotor::class.java, "fr") - this.bl = this.hardwareMap.get(DcMotor::class.java, "bl") - this.br = this.hardwareMap.get(DcMotor::class.java, "br") + this.fl = this.opMode.hardwareMap.get(DcMotor::class.java, "fl") + this.fr = this.opMode.hardwareMap.get(DcMotor::class.java, "fr") + this.bl = this.opMode.hardwareMap.get(DcMotor::class.java, "bl") + this.br = this.opMode.hardwareMap.get(DcMotor::class.java, "br") } // A public function that sets the power of all four wheels. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/TriWheels.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/TriWheels.kt index 61663bad..a38e4e7f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/TriWheels.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/TriWheels.kt @@ -26,9 +26,9 @@ object TriWheels : API() { override fun init(opMode: OpMode) { super.init(opMode) - this.red = hardwareMap.get(DcMotor::class.java, "redWheel") - this.green = hardwareMap.get(DcMotor::class.java, "greenWheel") - this.blue = hardwareMap.get(DcMotor::class.java, "blueWheel") + this.red = this.opMode.hardwareMap.get(DcMotor::class.java, "redWheel") + this.green = this.opMode.hardwareMap.get(DcMotor::class.java, "greenWheel") + this.blue = this.opMode.hardwareMap.get(DcMotor::class.java, "blueWheel") this.stopAndResetMotors() } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/AutoMain.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/AutoMain.kt index 78434b3b..5b3bcfd5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/AutoMain.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/AutoMain.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opmode.autonomous 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.teamcode.api.Box import org.firstinspires.ftc.teamcode.api.Drone import org.firstinspires.ftc.teamcode.api.Telemetry import org.firstinspires.ftc.teamcode.api.TriWheels @@ -31,85 +30,17 @@ abstract class AutoMain : LinearOpMode() { Telemetry.init(this) TriWheels.init(this) Encoders.init(this) - Box.init(this) Drone.init(this) - // Vision APIs - // AprilVision.init(this) - // Vision.init(this, AprilVision) - - // AprilMovement.init(this) - - // Modify camera exposure for april tags - // This may interfere with other vision processes like Tensorflow - // Vision.optimizeForAprilTags() - - // Stream camera to FTC Dashboard - // val camera = getVisionPortalCamera(Vision.portal)!! - // FtcDashboard.getInstance().startCameraStream(camera, 0.0) - Telemetry.sayInitialized() waitForStart() - /* - // TODO: Scan team game element - val teamElementPos = 2 - */ + Telemetry.sayStarted() sleep(RobotConfig.AutoMain.WAIT_TIME) - telemetry.log().add("No team game element scanned, defaulting to 2!") - telemetry.update() - - when (config.startPos) { - StartPos.BackStage -> { - Encoders.driveTo(forward, startingOffset) - Encoders.spinTo(pickTeam(90.0, -90.0)) - Encoders.driveTo(forward, tiles(1)) - Encoders.spinTo(pickTeam(-90.0, 90.0)) - Encoders.driveTo(forward, tiles(1)) - Encoders.spinTo(pickTeam(90.0, -90.0)) - Encoders.driveTo(forward, tiles(2)) - } - - StartPos.FrontStage -> { - // Drive forward two tiles - Encoders.driveTo(forward, tiles(2) + startingOffset) - - // Spin to face backdrop - Encoders.spinTo(pickTeam(90.0, -90.0)) - - Encoders.driveTo(forward, tiles(1)) - } - } - - /* - - // Deposit pixel using april tag - // Red: 1, 2, 3. Blue: 4, 5, 6 - AprilMovement.driveTo(teamElementPos + pickTeam(0, 3)) - - // TODO: Deposit pixel - - // Back up to view all april tags - Encoders.driveTo(forward, tiles(-1)) - - // Center 1 tile away from middle april tag - when (config.team) { - Team.Red -> AprilMovement.driveTo(5, tiles(1)) - Team.Blue -> AprilMovement.driveTo(2, tiles(1)) - } - - */ - - // Navigate to parking spot - Encoders.spinTo(pickParkPos(-90.0, 90.0)) - Encoders.driveTo(forward, tiles(1)) - Encoders.spinTo(pickParkPos(90.0, -90.0)) - - // Park in spot - Encoders.driveTo(forward, tiles(1)) + // TODO: Rest of the autonomous. } /** Converts an amount of tiles to inches. */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/DemoAutonomous.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/DemoAutonomous.kt index aab89944..255970ab 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/DemoAutonomous.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/DemoAutonomous.kt @@ -3,9 +3,9 @@ package org.firstinspires.ftc.teamcode.opmode.autonomous 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.util.ElapsedTime import org.firstinspires.ftc.teamcode.api.DemoQuadWheels import org.firstinspires.ftc.teamcode.api.Telemetry -import org.firstinspires.ftc.teamcode.components.linear.DemoSpinLinear @Autonomous(name = "Demo Autonomous") @Disabled @@ -26,7 +26,14 @@ class DemoAutonomous : LinearOpMode() { // Log that we are started Telemetry.sayStarted() - // Linear components are run in order - DemoSpinLinear.run(this) + val runtime = ElapsedTime() + + while (runtime.seconds() < 2.0) { + // Drive at 50% speed, slowing down the closer we get to 2 seconds. + DemoQuadWheels.drive(0.5 * (2.0 - runtime.seconds())) + } + + // Stop the robot. + DemoQuadWheels.drive(0.0) } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/JankAuto.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/JankAuto.kt index 8fb91b73..db8fa505 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/JankAuto.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/autonomous/JankAuto.kt @@ -1,3 +1,5 @@ +@file:Suppress("DEPRECATION") + package org.firstinspires.ftc.teamcode.opmode.autonomous import com.qualcomm.robotcore.eventloop.opmode.Autonomous diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/DemoTeleOp.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/DemoTeleOp.kt index 9f3688f0..4fd3a70e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/DemoTeleOp.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/DemoTeleOp.kt @@ -7,7 +7,6 @@ import org.firstinspires.ftc.teamcode.api.DemoQuadWheels import org.firstinspires.ftc.teamcode.api.Telemetry import org.firstinspires.ftc.teamcode.api.vision.AprilVision import org.firstinspires.ftc.teamcode.api.vision.Vision -import org.firstinspires.ftc.teamcode.components.DemoForward @TeleOp(name = "Demo TeleOp") @Disabled @@ -32,8 +31,17 @@ class DemoTeleOp : OpMode() { // Run repeatedly while the robot is running. override fun loop() { - // Runs the component. - DemoForward.loop(this) + val x = this.gamepad1.left_stick_x.toDouble() + val y = this.gamepad1.left_stick_y.toDouble() + val rotation = this.gamepad1.right_stick_x.toDouble() + + // Strafe + rotate robot using left and right joysticks. + DemoQuadWheels.drive( + x - y + rotation, + -x - y - rotation, + -x - y + rotation, + x - y - rotation, + ) // Log that we are running Telemetry.sayRunning() diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/TeleOpMain.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/TeleOpMain.kt index 60e38399..9ea8ae6f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/TeleOpMain.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/teleop/TeleOpMain.kt @@ -1,3 +1,5 @@ +@file:Suppress("DEPRECATION") + package org.firstinspires.ftc.teamcode.opmode.teleop import com.qualcomm.robotcore.eventloop.opmode.OpMode diff --git a/build.gradle b/build.gradle index 78db274c..0fbc9b81 100644 --- a/build.gradle +++ b/build.gradle @@ -6,7 +6,7 @@ buildscript { ext { - kotlin_version = '1.9.0' + kotlin_version = '1.9.22' } repositories { mavenCentral() @@ -14,7 +14,7 @@ buildscript { } dependencies { // Note for FTC Teams: Do not modify this yourself. - classpath 'com.android.tools.build:gradle:7.4.2' + classpath 'com.android.tools.build:gradle:8.2.1' classpath "org.jetbrains.kotlin:kotlin-gradle-plugin:$kotlin_version" } } diff --git a/gradle.properties b/gradle.properties index 93951271..a58cb1b3 100644 --- a/gradle.properties +++ b/gradle.properties @@ -8,3 +8,9 @@ android.enableJetifier=true org.gradle.jvmargs=-Xmx1024M # Force Kotlin official code style kotlin.code.style=official +# Disable auto-downloading of Java toolchains +org.gradle.java.installations.auto-download=false +# Gradle 8.0 config +android.defaults.buildfeatures.buildconfig=true +android.nonTransitiveRClass=false +android.nonFinalResIds=false diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index 907437ab..aaad91a2 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,6 @@ #Thu Dec 14 13:01:55 EST 2023 distributionBase=GRADLE_USER_HOME distributionPath=wrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-7.6.3-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.2-bin.zip zipStoreBase=GRADLE_USER_HOME zipStorePath=wrapper/dists