Skip to content

Commit

Permalink
The Great Refactor, Part I
Browse files Browse the repository at this point in the history
added teamcode module.
added READMEs to some modules.
moved lots of consts to Var object
deleted unused Zoom opmode
deleted unused RobotLocks.kt
  • Loading branch information
penguinencounter committed Nov 10, 2023
1 parent a205542 commit 3b27034
Show file tree
Hide file tree
Showing 40 changed files with 204 additions and 155 deletions.
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
package org.firstinspires.ftc.teamcode

import org.firstinspires.ftc.teamcode.odo.Pose
import org.firstinspires.ftc.teamcode.odo.degrees
import org.firstinspires.ftc.teamcode.odo.inches
import org.firstinspires.ftc.teamcode.utility.Vector2
import org.firstinspires.ftc.teamcode.utilities.Pose
import org.firstinspires.ftc.teamcode.utilities.Vector2
import org.firstinspires.ftc.teamcode.utilities.degrees
import org.firstinspires.ftc.teamcode.utilities.inches
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection
import kotlin.math.abs
import kotlin.math.cos
Expand Down
48 changes: 48 additions & 0 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Var.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
package org.firstinspires.ftc.teamcode
/*
* Servo rotations: minimum 0.0, maximum 1.0
*/
/**
* All the things that a driver might need to change, in one place.
*/
object Var {
// Rotations.

// 'hover' - just above ground
const val CLAW_HOVER_ROTATION = 0.669

// 'closing' - touching ground as much as possible without hindering claw operation
const val CLAW_CLOSING_ROTATION = 0.720

// 'flipped' - pixel drop-off location
const val CLAW_FLIPPED_ROTATION = 0.069

// 'stowed' - straight up or otherwise out of the way
const val CLAW_STOWED_ROTATION = 0.370

const val CLAW_OPENED = 0.109
const val CLAW_CLOSED = 0.432

/**
* The rotation of the box in the idle position.
* The box is in the idle position when it is not being dumped, and also when the lift
* is all the way down. Tune (DumperTestBench) with lift at 0 to avoid collisions.
*/
const val BOX_ROTATE_IDLE = 0.531

/**
* The rotation of the box in the dumping position.
* Tune with the lift raised by hand.
*/
const val BOX_ROTATE_DUMP = 0.316

/**
* Latch position such that it does not block movement of the bottom pixel in the box.
*/
const val BOX_LATCH_UNLATCHED = 0.4

/**
* Latch position such that it blocks movement of the bottom pixel in the box.
*/
const val BOX_LATCH_LATCHED = 0.78
}
24 changes: 0 additions & 24 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Variables.kt

This file was deleted.

22 changes: 0 additions & 22 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Zoom.java

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -7,23 +7,29 @@ import dev.aether.collaborative_multitasking.MultitaskScheduler
import dev.aether.collaborative_multitasking.SharedResource
import dev.aether.collaborative_multitasking.Task
import dev.aether.collaborative_multitasking.ext.maxDuration
import org.firstinspires.ftc.teamcode.ClawVar
import org.firstinspires.ftc.teamcode.Var

/**
* This class represents the robot's claw. For manual control of the claw's positions,
* get a reference to the Servo from your RobotConfiguration.
* @see org.firstinspires.ftc.teamcode.configurations.RobotConfiguration.clawGrab
* @see org.firstinspires.ftc.teamcode.configurations.RobotConfiguration.clawRotate
*
* @param scheduler Scheduler used to manage the claw's tasks. If null, then methods relying on
* the scheduler will throw an AssertionError.
* @param grip Servo used to control the claw's grip.
* @param rotate Servo used to control the claw's rotation.
* @param lock SharedResource used to prevent the claw's tasks from running at the same time as another.
*/
class Claw(
private val scheduler: MultitaskScheduler,
private val scheduler: MultitaskScheduler?,
@JvmField val grip: Servo,
@JvmField val rotate: Servo,
private val lock: SharedResource,
) {
companion object {
// Try to avoid changing these here. Instead, change them in Variables.kt.
const val ROTATE_HOVER = ClawVar.HoverRotation
const val ROTATE_CLOSING = ClawVar.ClosingRotation
const val ROTATE_FLIP = ClawVar.FlippedRotation
const val ROTATE_STOW = ClawVar.StowedRotation
const val GRIP_OPEN = ClawVar.ClawOpened
const val GRIP_CLOSED = ClawVar.ClawClosed
constructor(grip: Servo, rotate: Servo, lock: SharedResource) : this(null, grip, rotate, lock)

companion object {
// TODO trim timings
const val CloseRotateTime = 100 // ms
const val GripTime = 450 // ms
Expand All @@ -46,7 +52,14 @@ class Claw(

private var clawState: StateV2 = StateV2.Hover


/**
* Schedule a task to grab an item with the claw.
* Action is automatically cancelled if the claw is already in use.
*/
fun grab() {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
if (scheduler.isResourceInUse(lock)) return
// (dep: hover) open -> grab -> hover
var base: Task? = null
Expand All @@ -55,21 +68,27 @@ class Claw(
+lock
onStart { ->
clawState = StateV2.Active
grip.position = GRIP_OPEN
rotate.position = ROTATE_CLOSING
grip.position = Var.CLAW_OPENED
rotate.position = Var.CLAW_CLOSING_ROTATION
}
maxDuration(FlipTime)
}.then {
+lock
onStart { ->
grip.position = GRIP_CLOSED
grip.position = Var.CLAW_CLOSED
}
maxDuration(GripTime)
}.then(gotoHover())
base?.then(main)
}

/**
* Schedule a task to drop the item that is currently in the claw into the box.
* Action is automatically cancelled if the claw is already in use.
*/
fun deposit() {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
if (scheduler.isResourceInUse(lock)) return
// (dep: hover) -> deposit -> stowed
var base: Task? = null
Expand All @@ -78,19 +97,19 @@ class Claw(
+lock
onStart { ->
clawState = StateV2.Active
rotate.position = ROTATE_FLIP
rotate.position = Var.CLAW_FLIPPED_ROTATION
}
maxDuration(FlipTime)
}.then {
+lock
onStart { ->
grip.position = GRIP_OPEN
grip.position = Var.CLAW_OPENED
}
maxDuration(GripTime)
}.then {
+lock
onStart { ->
rotate.position = ROTATE_STOW
rotate.position = Var.CLAW_STOWED_ROTATION
}
maxDuration(FlipTime)
onFinish { ->
Expand All @@ -100,18 +119,30 @@ class Claw(
base?.then(main)
}

/**
* Schedule a task to move the claw to the hovering position.
* Action is automatically cancelled if the claw is already in use.
*/
fun resetTele() {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
if (scheduler.isResourceInUse(lock)) return
// (hover and open)
reset()
}

/**
* Schedule a task to move the claw to the hovering position.
*/
fun reset(): Task {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
return scheduler.task {
+lock
onStart { ->
clawState = StateV2.Active
grip.position = GRIP_OPEN
rotate.position = ROTATE_HOVER
grip.position = Var.CLAW_OPENED
rotate.position = Var.CLAW_HOVER_ROTATION
}
maxDuration(FlipTime)
onFinish { ->
Expand All @@ -121,10 +152,12 @@ class Claw(
}

private fun gotoHover(): Task {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
return scheduler.task {
+lock
onStart { ->
rotate.position = ROTATE_HOVER
rotate.position = Var.CLAW_HOVER_ROTATION
}
maxDuration(FlipTime)
onFinish { ->
Expand All @@ -133,13 +166,18 @@ class Claw(
}
}

/**
* WIP; schedules a task to open the claw.
*/
fun release(): Task {
scheduler
?: throw AssertionError("The Claw instance needs to be defined with a scheduler to use this method")
var base: Task? = null
if (clawState != StateV2.Hover) base = gotoHover()
val ext = scheduler.task {
+lock
onStart { ->
grip.position = GRIP_OPEN
grip.position = Var.CLAW_OPENED
}
maxDuration(GripTime)
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.abstractions
import dev.aether.collaborative_multitasking.MultitaskScheduler
import dev.aether.collaborative_multitasking.Task
import dev.aether.collaborative_multitasking.ext.maxDuration
import org.firstinspires.ftc.teamcode.Var
import org.firstinspires.ftc.teamcode.configurations.RobotConfiguration

class Dumper(
Expand All @@ -16,11 +17,6 @@ class Dumper(
private val lock = config.dumperLock

companion object {
const val ROTATE_IDLE = 0.531
const val ROTATE_DUMP = 0.316
const val UNLATCHED = 0.4
const val LATCHED = 0.78

// TODO trim timings
const val RotateTime = 1000 // ms
const val LatchTime = 200 // ms
Expand All @@ -41,8 +37,8 @@ class Dumper(
+lock
onStart { ->
dumperState = State.Dump
rotate.position = ROTATE_DUMP
latch.position = LATCHED
rotate.position = Var.BOX_ROTATE_DUMP
latch.position = Var.BOX_LATCH_LATCHED
}
maxDuration(RotateTime)
}
Expand All @@ -55,8 +51,8 @@ class Dumper(
+lock
onStart { ->
dumperState = State.Dump
rotate.position = ROTATE_DUMP
latch.position = LATCHED
rotate.position = Var.BOX_ROTATE_DUMP
latch.position = Var.BOX_LATCH_LATCHED
}
maxDuration(RotateTime)
}
Expand All @@ -65,7 +61,7 @@ class Dumper(
+lock
onStart { ->
dumperState = State.Dump2
latch.position = UNLATCHED
latch.position = Var.BOX_LATCH_UNLATCHED
}
maxDuration(LatchTime)
}
Expand All @@ -78,8 +74,8 @@ class Dumper(
+lock
onStart { ->
dumperState = State.Idle
rotate.position = ROTATE_IDLE
latch.position = LATCHED
rotate.position = Var.BOX_ROTATE_IDLE
latch.position = Var.BOX_LATCH_LATCHED
}
maxDuration(RotateTime)
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@ 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.utilities.MotorSet
import org.firstinspires.ftc.teamcode.utilities.typedGet

class NeoRobot1(map: HardwareMap) : RobotConfiguration() {
class Robot(map: HardwareMap) : RobotConfiguration() {
@JvmField
var frontLeft // 0
: DcMotor = map.typedGet("frontLeft")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@ import com.qualcomm.robotcore.hardware.HardwareMap
import com.qualcomm.robotcore.hardware.Servo
import dev.aether.collaborative_multitasking.SharedResource
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.firstinspires.ftc.teamcode.utility.MotorSet
import org.firstinspires.ftc.teamcode.utilities.MotorSet

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

protected abstract val driveMotors: MotorSet?
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@ package org.firstinspires.ftc.teamcode.odo
import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.util.ElapsedTime
import dev.aether.collaborative_multitasking.Task
import org.firstinspires.ftc.teamcode.utilities.LengthUnit
import org.firstinspires.ftc.teamcode.utilities.Pose
import org.firstinspires.ftc.teamcode.utilities.inches
import java.util.concurrent.TimeUnit

class OdoTracker(val odoPerp: DcMotor, val odoPara1: DcMotor, val odoPara2: DcMotor, val origin: Pose) {
Expand Down
Loading

0 comments on commit 3b27034

Please sign in to comment.