From ce13986856ecf5a6659975f1b63e8ee76806d378 Mon Sep 17 00:00:00 2001 From: Sachet Korada Date: Sat, 30 Nov 2024 10:31:10 -0500 Subject: [PATCH] Refactor CRServo to Servo --- .../commands/intake/IntakeBeltCommand.kt | 6 +----- .../teamcode/commands/intake/IntakeCommand.kt | 4 ---- .../opModes/auto/blue/basket/left/Blue1Plus1.kt | 11 +++-------- .../auto/blue/basket/left/BlueHighBasketLeft.kt | 6 +++--- .../blue/basket/right/BlueHighBasketRight.kt | 10 +++++----- .../blue/chamber/left/BlueHighChamberLeft.kt | 7 ++++--- .../blue/chamber/right/BlueHighChamberRight.kt | 7 ++++--- .../auto/red/basket/left/RedHighBasketLeft.kt | 7 ++++--- .../auto/red/basket/right/RedHighBasketRight.kt | 7 ++++--- .../auto/red/chamber/left/RedHighChamberLeft.kt | 7 ++++--- .../red/chamber/right/RedHighChamberRight.kt | 7 ++++--- .../ftc/teamcode/opModes/teleOp/MainTeleOp.kt | 5 ++--- .../ftc/teamcode/opModes/tuning/IntakeTuner.kt | 6 +++--- .../roadrunner/AutomaticFeedforwardTuner.kt | 1 - .../opModes/tuning/roadrunner/BackAndForth.kt | 1 - .../tuning/roadrunner/DriveVelocityPIDTuner.kt | 1 - .../tuning/roadrunner/FollowerPIDTuner.kt | 1 - .../tuning/roadrunner/LocalizationTest.kt | 1 - .../tuning/roadrunner/ManualFeedforwardTuner.kt | 1 - .../tuning/roadrunner/MaxAngularVeloTuner.kt | 1 - .../tuning/roadrunner/MaxVelocityTuner.kt | 1 - .../tuning/roadrunner/MotorDirectionDebugger.kt | 1 - .../opModes/tuning/roadrunner/SplineTest.kt | 1 - .../opModes/tuning/roadrunner/StrafeTest.kt | 1 - .../opModes/tuning/roadrunner/StraightTest.kt | 1 - .../opModes/tuning/roadrunner/TrackWidthTuner.kt | 1 - .../TrackingWheelForwardOffsetTuner.kt | 1 - .../TrackingWheelLateralDistanceTuner.kt | 1 - .../opModes/tuning/roadrunner/TurnTest.kt | 1 - .../subsystems/intake/IntakeBeltSubsystem.kt | 4 ++-- .../subsystems/intake/IntakeSubsystem.kt | 16 +++++++++------- .../subsystems/slides/OpenElevatorSubsystem.kt | 4 ++-- 32 files changed, 54 insertions(+), 76 deletions(-) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeBeltCommand.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeBeltCommand.kt index 9d0f345..6f0ab52 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeBeltCommand.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeBeltCommand.kt @@ -15,8 +15,4 @@ class IntakeBeltCommand( intakeBeltSubsystem.outtakePos() } } - - /* override fun end(interrupted: Boolean) { - intakeBeltSubsystem.stop() - } -*/} \ No newline at end of file +} \ No newline at end of file diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeCommand.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeCommand.kt index b994fd8..bd9429c 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeCommand.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/IntakeCommand.kt @@ -15,8 +15,4 @@ class IntakeCommand( subsystem.outtake() } } - - override fun end(interrupted: Boolean) { - subsystem.stop() - } } \ No newline at end of file diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/Blue1Plus1.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/Blue1Plus1.kt index 3f7a4f7..ade1c44 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/Blue1Plus1.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/Blue1Plus1.kt @@ -1,7 +1,6 @@ package org.firstinspires.ftc.teamcode.opModes.auto.blue.basket.left import com.acmerobotics.roadrunner.geometry.Pose2d -import com.arcrobotics.ftclib.hardware.motors.CRServo import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode @@ -21,7 +20,7 @@ class Blue1Plus1: OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var intakeBelt: Servo private lateinit var driveSubsystem: DriveSubsystem @@ -31,7 +30,7 @@ class Blue1Plus1: OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) intakeBelt = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE_BELT.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) @@ -64,11 +63,7 @@ class Blue1Plus1: OpMode() { .addTemporalMarker(8.0) { intakeSubsystem.outtake() } - .waitSeconds(0.5) - .addTemporalMarker(8.5) { - intakeSubsystem.stop() - } - .waitSeconds(1.0) + .waitSeconds(1.5) .forward(4.0) .addTemporalMarker(9.5) { elevatorSubsystem.setpoint = 0.0 diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/BlueHighBasketLeft.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/BlueHighBasketLeft.kt index 461264b..27e2886 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/BlueHighBasketLeft.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/left/BlueHighBasketLeft.kt @@ -1,9 +1,9 @@ package org.firstinspires.ftc.teamcode.opModes.auto.blue.basket.left -import com.arcrobotics.ftclib.hardware.motors.CRServo import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +18,7 @@ class BlueHighBasketLeft: OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +26,7 @@ class BlueHighBasketLeft: OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/right/BlueHighBasketRight.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/right/BlueHighBasketRight.kt index 96b881c..f95d0c7 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/right/BlueHighBasketRight.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/basket/right/BlueHighBasketRight.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.blue.basket.right -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -13,14 +14,13 @@ import org.firstinspires.ftc.teamcode.subsystems.slides.ElevatorSubsystem @Autonomous(name = "Blue High Basket Right", group = "Basket", preselectTeleOp = "MainTeleOp") -class BlueHighBasketRight() : OpMode() { - +class BlueHighBasketRight : OpMode() { private lateinit var armLeft: Motor private lateinit var armRight: Motor private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -28,7 +28,7 @@ class BlueHighBasketRight() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/left/BlueHighChamberLeft.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/left/BlueHighChamberLeft.kt index 6b537df..c98fab0 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/left/BlueHighChamberLeft.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/left/BlueHighChamberLeft.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.blue.chamber.left -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +19,7 @@ class BlueHighChamberLeft() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +27,7 @@ class BlueHighChamberLeft() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/right/BlueHighChamberRight.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/right/BlueHighChamberRight.kt index ceecd1a..bd59302 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/right/BlueHighChamberRight.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/blue/chamber/right/BlueHighChamberRight.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.blue.chamber.right -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +19,7 @@ class BlueHighChamberRight() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +27,7 @@ class BlueHighChamberRight() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/left/RedHighBasketLeft.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/left/RedHighBasketLeft.kt index 74630a7..774470f 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/left/RedHighBasketLeft.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/left/RedHighBasketLeft.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.red.basket.left -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -19,7 +20,7 @@ class RedHighBasketLeft() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -27,7 +28,7 @@ class RedHighBasketLeft() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/right/RedHighBasketRight.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/right/RedHighBasketRight.kt index 657d3ef..ea4cd44 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/right/RedHighBasketRight.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/basket/right/RedHighBasketRight.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.red.basket.right -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +19,7 @@ class RedHighBasketRight() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +27,7 @@ class RedHighBasketRight() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/left/RedHighChamberLeft.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/left/RedHighChamberLeft.kt index fe3b6a5..d59365a 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/left/RedHighChamberLeft.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/left/RedHighChamberLeft.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.red.chamber.left -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +19,7 @@ class RedHighChamberLeft() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +27,7 @@ class RedHighChamberLeft() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/right/RedHighChamberRight.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/right/RedHighChamberRight.kt index 671b539..7bb7257 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/right/RedHighChamberRight.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/auto/red/chamber/right/RedHighChamberRight.kt @@ -1,9 +1,10 @@ package org.firstinspires.ftc.teamcode.opModes.auto.red.chamber.right -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.Autonomous import com.qualcomm.robotcore.eventloop.opmode.OpMode +import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.AutoStartPose import org.firstinspires.ftc.teamcode.constants.ControlBoard import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem @@ -18,7 +19,7 @@ class RedHighChamberRight() : OpMode() { private lateinit var elevatorLeft: Motor private lateinit var elevatorRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var driveSubsystem: DriveSubsystem private lateinit var intakeSubsystem: IntakeSubsystem @@ -26,7 +27,7 @@ class RedHighChamberRight() : OpMode() { private lateinit var elevatorSubsystem: ElevatorSubsystem override fun init() { - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName) armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt index 1d8b37a..7d2332b 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt @@ -7,7 +7,6 @@ import com.arcrobotics.ftclib.command.RunCommand import com.arcrobotics.ftclib.command.button.Trigger import com.arcrobotics.ftclib.gamepad.GamepadEx import com.arcrobotics.ftclib.gamepad.GamepadKeys -import com.arcrobotics.ftclib.hardware.motors.CRServo import com.arcrobotics.ftclib.hardware.motors.Motor import com.qualcomm.robotcore.eventloop.opmode.TeleOp import com.qualcomm.robotcore.hardware.Servo @@ -30,7 +29,7 @@ class MainTeleOp : CommandOpMode() { private lateinit var armLeft: Motor private lateinit var armRight: Motor - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var intakeBelt: Servo private lateinit var slidesSubsystem: OpenElevatorSubsystem @@ -69,7 +68,7 @@ class MainTeleOp : CommandOpMode() { armRight = Motor(hardwareMap, ControlBoard.ARM_RIGHT.deviceName, Motor.GoBILDA.RPM_60) armLeft = Motor(hardwareMap, ControlBoard.ARM_LEFT.deviceName, Motor.GoBILDA.RPM_60) - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) intakeBelt = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE_BELT.deviceName) armSubsystem = OpenArmSubsystem(armRight, armLeft) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/IntakeTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/IntakeTuner.kt index a74aec4..acd7294 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/IntakeTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/IntakeTuner.kt @@ -5,7 +5,7 @@ import com.acmerobotics.dashboard.config.Config import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.arcrobotics.ftclib.command.CommandOpMode import com.arcrobotics.ftclib.command.RunCommand -import com.arcrobotics.ftclib.hardware.motors.CRServo + import com.qualcomm.robotcore.eventloop.opmode.TeleOp import com.qualcomm.robotcore.hardware.Servo import org.firstinspires.ftc.teamcode.constants.ControlBoard @@ -15,7 +15,7 @@ import org.firstinspires.ftc.teamcode.subsystems.intake.IntakeSubsystem @TeleOp @Config class IntakeTuner : CommandOpMode() { - private lateinit var intake: CRServo + private lateinit var intake: Servo private lateinit var intakeBelt: Servo private lateinit var intakeSubsystem: IntakeSubsystem @@ -24,7 +24,7 @@ class IntakeTuner : CommandOpMode() { override fun initialize() { telemetry = MultipleTelemetry(telemetry, FtcDashboard.getInstance().telemetry) - intake = CRServo(hardwareMap, ControlBoard.INTAKE.deviceName) + intake = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE.deviceName) intakeBelt = hardwareMap.get(Servo::class.java, ControlBoard.INTAKE_BELT.deviceName) intakeSubsystem = IntakeSubsystem(intake) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/AutomaticFeedforwardTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/AutomaticFeedforwardTuner.kt index ca3f37a..e61f24a 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/AutomaticFeedforwardTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/AutomaticFeedforwardTuner.kt @@ -6,7 +6,6 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d import com.acmerobotics.roadrunner.util.NanoClock 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.RobotLog import org.firstinspires.ftc.robotcore.internal.system.Misc diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/BackAndForth.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/BackAndForth.kt index 7441dfb..ad60cfc 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/BackAndForth.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/BackAndForth.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.dashboard.config.Config import com.acmerobotics.roadrunner.geometry.Pose2d 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/DriveVelocityPIDTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/DriveVelocityPIDTuner.kt index 1448fbe..521f1ba 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/DriveVelocityPIDTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/DriveVelocityPIDTuner.kt @@ -9,7 +9,6 @@ import com.acmerobotics.roadrunner.profile.MotionProfileGenerator.generateSimple import com.acmerobotics.roadrunner.profile.MotionState import com.acmerobotics.roadrunner.util.NanoClock 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.DcMotor import com.qualcomm.robotcore.util.RobotLog diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/FollowerPIDTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/FollowerPIDTuner.kt index cd31e54..7f99231 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/FollowerPIDTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/FollowerPIDTuner.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.dashboard.config.Config import com.acmerobotics.roadrunner.geometry.Pose2d 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/LocalizationTest.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/LocalizationTest.kt index c94f85d..634d631 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/LocalizationTest.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/LocalizationTest.kt @@ -1,7 +1,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.roadrunner.geometry.Pose2d -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 diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/ManualFeedforwardTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/ManualFeedforwardTuner.kt index 2a731d9..ff1b6dc 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/ManualFeedforwardTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/ManualFeedforwardTuner.kt @@ -10,7 +10,6 @@ import com.acmerobotics.roadrunner.profile.MotionProfileGenerator.generateSimple import com.acmerobotics.roadrunner.profile.MotionState import com.acmerobotics.roadrunner.util.NanoClock 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.RobotLog import org.firstinspires.ftc.teamcode.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxAngularVeloTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxAngularVeloTuner.kt index f61aaac..66cfa58 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxAngularVeloTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxAngularVeloTuner.kt @@ -5,7 +5,6 @@ import com.acmerobotics.dashboard.config.Config import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d 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.DcMotor import com.qualcomm.robotcore.util.ElapsedTime diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxVelocityTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxVelocityTuner.kt index 93dd051..b31c201 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxVelocityTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MaxVelocityTuner.kt @@ -4,7 +4,6 @@ import com.acmerobotics.dashboard.FtcDashboard import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d 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.DcMotor import com.qualcomm.robotcore.hardware.VoltageSensor diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MotorDirectionDebugger.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MotorDirectionDebugger.kt index e035dcc..a865cd0 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MotorDirectionDebugger.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/MotorDirectionDebugger.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.dashboard.FtcDashboard import com.acmerobotics.dashboard.config.Config import com.acmerobotics.dashboard.telemetry.MultipleTelemetry -import com.qualcomm.robotcore.eventloop.opmode.Disabled import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode import com.qualcomm.robotcore.eventloop.opmode.TeleOp import org.firstinspires.ftc.robotcore.external.Telemetry diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/SplineTest.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/SplineTest.kt index afff7a9..0849b10 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/SplineTest.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/SplineTest.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.roadrunner.geometry.Pose2d import com.acmerobotics.roadrunner.geometry.Vector2d 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StrafeTest.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StrafeTest.kt index cf637cd..5e6765a 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StrafeTest.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StrafeTest.kt @@ -5,7 +5,6 @@ import com.acmerobotics.dashboard.config.Config import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StraightTest.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StraightTest.kt index cd63379..8088288 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StraightTest.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/StraightTest.kt @@ -5,7 +5,6 @@ import com.acmerobotics.dashboard.config.Config import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackWidthTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackWidthTuner.kt index 740b73b..0f849d2 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackWidthTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackWidthTuner.kt @@ -6,7 +6,6 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d import com.acmerobotics.roadrunner.util.Angle.norm 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.MovingStatistics import org.firstinspires.ftc.robotcore.internal.system.Misc diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelForwardOffsetTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelForwardOffsetTuner.kt index d21ba97..14e12ff 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelForwardOffsetTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelForwardOffsetTuner.kt @@ -6,7 +6,6 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry import com.acmerobotics.roadrunner.geometry.Pose2d import com.acmerobotics.roadrunner.util.Angle.norm 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.MovingStatistics import com.qualcomm.robotcore.util.RobotLog diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelLateralDistanceTuner.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelLateralDistanceTuner.kt index 32e4c47..0d52efe 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelLateralDistanceTuner.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TrackingWheelLateralDistanceTuner.kt @@ -3,7 +3,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.dashboard.config.Config import com.acmerobotics.roadrunner.geometry.Pose2d import com.acmerobotics.roadrunner.util.Angle.normDelta -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.util.RobotLog diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TurnTest.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TurnTest.kt index 5345621..c82dcc9 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TurnTest.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/tuning/roadrunner/TurnTest.kt @@ -2,7 +2,6 @@ package org.firstinspires.ftc.teamcode.opModes.tuning.roadrunner import com.acmerobotics.dashboard.config.Config 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.subsystems.drive.DriveSubsystem diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeBeltSubsystem.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeBeltSubsystem.kt index 63e1c00..7c4fbeb 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeBeltSubsystem.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeBeltSubsystem.kt @@ -9,12 +9,12 @@ class IntakeBeltSubsystem( var intakePos = false fun outtakePos() { - intakeBelt.position = 0.0 + intakeBelt.position = 0.25 intakePos = true } fun intakePos() { - intakeBelt.position = 0.6 + intakeBelt.position = 0.02 intakePos = false } diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt index 1d360fd..b06f22b 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt @@ -1,16 +1,18 @@ package org.firstinspires.ftc.teamcode.subsystems.intake import com.arcrobotics.ftclib.command.SubsystemBase -import com.arcrobotics.ftclib.hardware.motors.CRServo +import com.qualcomm.robotcore.hardware.Servo class IntakeSubsystem( - private val intake: CRServo + private val intake: Servo ) : SubsystemBase() { - fun intake() = intake.set(1.0) + fun intake() { + intake.position = 1.0 + } - fun outtake() = intake.set(-0.5) + fun outtake() { + intake.position = 0.0 + } - fun setSpeed(speed: Double) = intake.set(speed) - - fun stop() = intake.stop() + fun setSpeed(speed: Double) { intake.position = speed } } \ No newline at end of file diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/slides/OpenElevatorSubsystem.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/slides/OpenElevatorSubsystem.kt index e49c72d..a7f36fc 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/slides/OpenElevatorSubsystem.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/slides/OpenElevatorSubsystem.kt @@ -21,11 +21,11 @@ class OpenElevatorSubsystem( // Functions for moving slides up and down, number being speed, 1 being 100% fun up() { - elevatorMotors.set(1.0) + elevatorMotors.set(0.7) } fun down() { - elevatorMotors.set(-1.0) + elevatorMotors.set(-0.7) } fun stop() {