Skip to content

Commit

Permalink
Kotlin stuff, refactoring
Browse files Browse the repository at this point in the history
+ *rename* Loq => SharedResource because the multithreading parallels are kinda cringe idk
+ Add a bunch of `@JvmField` and `@JvmOverloads` annotations
+ Add RobotConfiguration abstract class
+ MotorPowers: normalization, operator functions
+ SharedResource and Scheduler panic()s (cleanup functions)
+ Deprecate RobotLocks.kt object
+ Delete commented code in Task.kt
+ Claw now takes lock as constructor argument
  • Loading branch information
penguinencounter committed Oct 21, 2023
1 parent da607ec commit 78169e4
Show file tree
Hide file tree
Showing 15 changed files with 232 additions and 125 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,12 @@

import android.annotation.SuppressLint;

import com.acmerobotics.dashboard.FtcDashboard;
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.hardware.camera.BuiltinCameraDirection;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.VisionPortal;
import org.firstinspires.ftc.vision.VisionProcessor;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import static org.firstinspires.ftc.teamcode.utility.CollectionUtils.pairs;

import android.util.Pair;
import android.util.Size;

import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@

import java.util.concurrent.TimeUnit;

import dev.aether.collaborative_multitasking.Loq;
import dev.aether.collaborative_multitasking.SharedResource;
import dev.aether.collaborative_multitasking.MultitaskScheduler;

@Autonomous
public class ExampleScheduledAuto extends LinearOpMode {
MultitaskScheduler scheduler;
public static final Loq EXAMPLE_LOCK = new Loq("example");
public static final SharedResource EXAMPLE_LOCK = new SharedResource("example");

@Override
public void runOpMode() {
Expand Down
32 changes: 15 additions & 17 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TeleOp.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;

import org.firstinspires.ftc.teamcode.abstractions.Claw;
import org.firstinspires.ftc.teamcode.configurations.NeoRobot1;
import org.firstinspires.ftc.teamcode.configurations.RobotConfiguration;
import org.firstinspires.ftc.teamcode.utility.MotorSet;

import java.util.concurrent.TimeUnit;

Expand All @@ -30,10 +30,10 @@ private double max(double a, double... others) {
@Override
public void runOpMode() {
MultitaskScheduler scheduler = new MultitaskScheduler();
Servo clawGrab = hardwareMap.get(Servo.class, "clawGrab");
Servo clawRotate = hardwareMap.get(Servo.class, "clawRotate");
Claw claw = new Claw(scheduler, clawGrab, clawRotate);
NeoRobot1 config = new NeoRobot1(hardwareMap);
RobotConfiguration robot = RobotConfiguration.currentConfiguration().invoke(hardwareMap);
if (robot == null) throw new RuntimeException("Robot configuration not found");
MotorSet driveMotors = robot.driveMotors();
Claw claw = new Claw(scheduler, robot.clawGrab(), robot.clawRotate(), robot.getClawLock());
waitForStart();
int targetLeft = 0;
int targetRight = 0;
Expand Down Expand Up @@ -74,10 +74,11 @@ public void runOpMode() {
int SLIDE_LIM = 3000;
int MOTION_PER_CYCLE = 20;

config.frontLeft.setPower(frontLeftPower * balFL);
config.backLeft.setPower(backLeftPower * balBL);
config.frontRight.setPower(frontRightPower * balFR);
config.backRight.setPower(backRightPower * balBR);

driveMotors.frontLeft.setPower(frontLeftPower * balFL);
driveMotors.backLeft.setPower(backLeftPower * balBL);
driveMotors.frontRight.setPower(frontRightPower * balFR);
driveMotors.backRight.setPower(backRightPower * balBR);

if (gamepad2.b) {
targetLeft = targets[0];
Expand Down Expand Up @@ -108,15 +109,12 @@ public void runOpMode() {
claw.reset();
}

config.slideLeft.setTargetPosition(targetLeft);
config.slideRight.setTargetPosition(targetRight);
robot.liftLeft().setTargetPosition(targetLeft);
robot.liftRight().setTargetPosition(targetRight);

sleep(5);
}

config.frontLeft.setPower(0);
config.backLeft.setPower(0);
config.frontRight.setPower(0);
config.backRight.setPower(0);
scheduler.panic();
driveMotors.setAll(0);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,16 @@
package org.firstinspires.ftc.teamcode.abstractions

import com.qualcomm.robotcore.hardware.Servo
import dev.aether.collaborative_multitasking.SharedResource
import dev.aether.collaborative_multitasking.MultitaskScheduler
import dev.aether.collaborative_multitasking.Task
import dev.aether.collaborative_multitasking.ext.maxDuration
import org.firstinspires.ftc.teamcode.configurations.RobotLocks

class Claw(
private val scheduler: MultitaskScheduler,
private val grip: Servo,
private val rotate: Servo
@JvmField val grip: Servo,
@JvmField val rotate: Servo,
private val lock: SharedResource,
) {
companion object {
const val ROTATE_HOVER = 0.83
Expand Down Expand Up @@ -43,20 +44,20 @@ class Claw(
private var clawState: StateV2 = StateV2.Hover

fun grab() {
if (scheduler.isResourceInUse(RobotLocks.claw)) return
if (scheduler.isResourceInUse(lock)) return
// (dep: hover) open -> grab -> hover
var base: Task? = null
if (clawState != StateV2.Hover) base = gotoHover()
val main = scheduler.task {
+RobotLocks.claw
+lock
onStart { ->
clawState = StateV2.Active
grip.position = GRIP_OPEN
rotate.position = ROTATE_CLOSING
}
maxDuration(FlipTime)
}.then {
+RobotLocks.claw
+lock
onStart { ->
grip.position = GRIP_CLOSED
}
Expand All @@ -66,25 +67,25 @@ class Claw(
}

fun deposit() {
if (scheduler.isResourceInUse(RobotLocks.claw)) return
if (scheduler.isResourceInUse(lock)) return
// (dep: hover) -> deposit -> stowed
var base: Task? = null
if (clawState != StateV2.Hover) base = gotoHover()
val main = scheduler.task {
+RobotLocks.claw
+lock
onStart { ->
clawState = StateV2.Active
rotate.position = ROTATE_FLIP
}
maxDuration(FlipTime)
}.then {
+RobotLocks.claw
+lock
onStart { ->
grip.position = GRIP_OPEN
}
maxDuration(GripTime)
}.then {
+RobotLocks.claw
+lock
onStart { ->
rotate.position = ROTATE_STOW
}
Expand All @@ -97,10 +98,10 @@ class Claw(
}

fun reset() {
if (scheduler.isResourceInUse(RobotLocks.claw)) return
if (scheduler.isResourceInUse(lock)) return
// (hover and open)
scheduler.task {
+RobotLocks.claw
+lock
onStart { ->
clawState = StateV2.Active
grip.position = GRIP_OPEN
Expand All @@ -115,7 +116,7 @@ class Claw(

private fun gotoHover(): Task {
return scheduler.task {
+RobotLocks.claw
+lock
onStart { ->
rotate.position = ROTATE_HOVER
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,50 +1,83 @@
package org.firstinspires.ftc.teamcode.configurations;
package org.firstinspires.ftc.teamcode.configurations

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.hardware.DcMotorSimple
import com.qualcomm.robotcore.hardware.HardwareMap
import com.qualcomm.robotcore.hardware.Servo
import dev.aether.collaborative_multitasking.SharedResource
import org.firstinspires.ftc.teamcode.utility.MotorSet
import org.firstinspires.ftc.teamcode.utility.typedGet

import org.firstinspires.ftc.teamcode.utility.MotorSet;
class NeoRobot1(map: HardwareMap) : RobotConfiguration() {
@JvmField
var frontLeft // 0
: DcMotor = map.typedGet("frontLeft")

public class NeoRobot1 {
public DcMotor frontLeft; // 0
public DcMotor frontRight; // 1
public DcMotor backLeft; // 2
public DcMotor backRight; // 3
@JvmField
var frontRight // 1
: DcMotor = map.typedGet("frontRight")

public DcMotor slideLeft; // 0
public DcMotor slideRight; // 1
@JvmField
var backLeft // 2
: DcMotor = map.typedGet("backLeft")

private static void reverse(DcMotor target) {
target.setDirection(DcMotorSimple.Direction.REVERSE);
}
private static void brake(DcMotor ...targets) {
for (DcMotor target : targets ) target.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
}
@JvmField
var backRight // 3
: DcMotor = map.typedGet("backRight")

@JvmField
var liftLeftB // 0
: DcMotor = map.typedGet("slideLeft")

@JvmField
var liftRightB // 1
: DcMotor = map.typedGet("slideRight")

@JvmField
var clawGrabB
: Servo = map.typedGet("clawGrab")

public NeoRobot1(HardwareMap map) {
frontLeft = map.get(DcMotor.class, "frontLeft");
reverse(frontLeft);
frontRight = map.get(DcMotor.class, "frontRight");
backLeft = map.get(DcMotor.class, "backLeft");
reverse(backLeft);
backRight = map.get(DcMotor.class, "backRight");
brake(frontLeft, frontRight, backLeft, backRight);

slideLeft = map.get(DcMotor.class, "slideLeft");
slideLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
slideLeft.setTargetPosition(0);
slideLeft.setPower(1);
slideLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
slideRight = map.get(DcMotor.class, "slideRight");
slideRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
slideRight.setTargetPosition(0);
slideRight.setPower(1);
slideRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
reverse(slideRight);
@JvmField
var clawRotateB
: Servo = map.typedGet("clawRotate")


override val driveMotors: MotorSet = MotorSet(frontLeft, frontRight, backLeft, backRight)
override val driveMotorLock: SharedResource
get() = SharedResource("driveMotors") {
driveMotors.setAll(
0.0
)
}
override val clawGrab: Servo get() = clawGrabB
override val clawRotate: Servo get() = clawRotateB
override val clawLock: SharedResource = SharedResource("claw")
override val liftLeft: DcMotor get() = liftLeftB
override val liftRight: DcMotor get() = liftRightB

init {
setReverse(frontLeft)
setReverse(backLeft)
enableBrakes(frontLeft, frontRight, backLeft, backRight)

liftLeftB.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftLeftB.targetPosition = 0
liftLeftB.power = 1.0
liftLeftB.mode = DcMotor.RunMode.RUN_TO_POSITION
liftRightB.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftRightB.targetPosition = 0
liftRightB.power = 1.0
liftRightB.mode = DcMotor.RunMode.RUN_TO_POSITION
setReverse(liftRightB)
}

public MotorSet getMotorSet() {
return new MotorSet(frontLeft, frontRight, backLeft, backRight);
companion object {
private fun setReverse(target: DcMotor) {
target.direction = DcMotorSimple.Direction.REVERSE
}

private fun enableBrakes(vararg targets: DcMotor) {
for (target in targets) target.zeroPowerBehavior = DcMotor.ZeroPowerBehavior.BRAKE
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.firstinspires.ftc.teamcode.configurations

import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.hardware.HardwareMap
import com.qualcomm.robotcore.hardware.Servo
import dev.aether.collaborative_multitasking.SharedResource
import org.firstinspires.ftc.teamcode.utility.MotorSet

abstract class RobotConfiguration {
companion object {
@JvmStatic
fun currentConfiguration(): (HardwareMap) -> RobotConfiguration = ::NeoRobot1
}

protected abstract val driveMotors: MotorSet?
fun driveMotors(): MotorSet = driveMotors ?: throw NullPointerException("Robot configuration has no drive motors but they were requested")

abstract val driveMotorLock: SharedResource

protected abstract val clawGrab: Servo?
fun clawGrab(): Servo = clawGrab ?: throw NullPointerException("Robot configuration has no claw grab servo but it was requested")
protected abstract val clawRotate: Servo?
fun clawRotate(): Servo = clawRotate ?: throw NullPointerException("Robot configuration has no claw rotate servo but it was requested")
abstract val clawLock: SharedResource

protected abstract val liftLeft: DcMotor?
fun liftLeft(): DcMotor = liftLeft ?: throw NullPointerException("Robot configuration has no left lift motor but it was requested")
protected abstract val liftRight: DcMotor?
fun liftRight(): DcMotor = liftRight ?: throw NullPointerException("Robot configuration has no right lift motor but it was requested")
}
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
package org.firstinspires.ftc.teamcode.configurations

import dev.aether.collaborative_multitasking.Loq
import dev.aether.collaborative_multitasking.SharedResource

object RobotLocks {
val driveMotors = Loq("driveMotors")
val liftLeft = Loq("driveMotors")
val liftRight = Loq("driveMotors")
val claw = Loq("claw")
@Deprecated("Use a RobotConfiguration's locks for panic support.")
val driveMotors = SharedResource("driveMotors")
}
Loading

0 comments on commit 78169e4

Please sign in to comment.