From cc8b86492115756c8e6a4cd1fcc3fc98f9d8a48d Mon Sep 17 00:00:00 2001 From: Ishaan Ghaskadbi Date: Sat, 30 Nov 2024 22:30:07 -0500 Subject: [PATCH] more updates --- .../firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt | 2 +- .../firstinspires/ftc/teamcode/opModes/tuning/IntakeTuner.kt | 2 +- .../ftc/teamcode/subsystems/arm/OpenArmSubsystem.kt | 4 +++- .../ftc/teamcode/subsystems/slides/OpenElevatorSubsystem.kt | 5 ++++- 4 files changed, 9 insertions(+), 4 deletions(-) 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 5e733f1..d26b03d 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 @@ -144,6 +144,6 @@ class MainTeleOp : CommandOpMode() { companion object { @JvmField - var kT = 0.05 + var kT = 0.005 } } \ No newline at end of file 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 acd7294..6fa8a7a 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 @@ -45,6 +45,6 @@ class IntakeTuner : CommandOpMode() { var speed = 0.0 @JvmField - var position = 1.0 + var position = 0.0 } } \ No newline at end of file diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/arm/OpenArmSubsystem.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/arm/OpenArmSubsystem.kt index 11d128f..7877fd7 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/arm/OpenArmSubsystem.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/arm/OpenArmSubsystem.kt @@ -6,6 +6,7 @@ import com.arcrobotics.ftclib.hardware.motors.Motor import com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA import com.arcrobotics.ftclib.hardware.motors.MotorGroup import org.firstinspires.ftc.teamcode.constants.ArmConstants +import org.firstinspires.ftc.teamcode.opModes.teleOp.MainTeleOp.Companion.kT import kotlin.math.PI import kotlin.math.cos @@ -40,7 +41,8 @@ class OpenArmSubsystem( } fun stop() { - turnMotors.set(ArmConstants.kCos.value * cos(armAngle)) + turnMotors.set(ArmConstants.kCos.value * cos(armAngle) + + kT * slidePos.invoke()) } companion object { 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 716250b..3cdd8f2 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 @@ -18,7 +18,10 @@ class OpenElevatorSubsystem( get() = elevatorMotors.positions[0] * SlidesConstants.MAX_HEIGHT_INCH.value / SlidesConstants.MAX_HEIGHT_TICKS.value init { - elevatorLeft.inverted = true + elevatorRight.inverted = true + elevatorRight.encoder.setDirection(Motor.Direction.REVERSE) + + elevatorMotors.resetEncoder() } // Functions for moving slides up and down, number being speed, 1 being 100%