Skip to content
This repository has been archived by the owner on Mar 17, 2024. It is now read-only.

Commit

Permalink
feat: api dependencies (#52)
Browse files Browse the repository at this point in the history
  • Loading branch information
BD103 authored Jan 25, 2024
2 parents 2da7117 + 0339377 commit 4a6ffb0
Show file tree
Hide file tree
Showing 6 changed files with 194 additions and 32 deletions.
99 changes: 92 additions & 7 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/API.kt
Original file line number Diff line number Diff line change
@@ -1,24 +1,57 @@
package org.firstinspires.ftc.teamcode.api

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.hardware.HardwareMap
import org.firstinspires.ftc.teamcode.utils.APIDependencies
import org.firstinspires.ftc.teamcode.utils.Resettable

/**
* An API is shared code used by components.
* An API is shared code used by opmodes.
*
* An API needs to be initialized with the [init] function before it can be used. In general, APIs
* should not have side-effects unless told to by a component.
* should not have side-effects unless one of their functions is called. [init] should only be
* called once per opmode.
*
* If an API depends on another API, it should say so in the object documentation.
* If an API requires methods only provided by a [LinearOpMode], it must override [isLinear] and set
* it to `true`. It can then access the [linearOpMode] property, which is like [opMode] but casted
* to the [LinearOpMode] type.
*
* An API can specify that it depends on another API by overriding the [dependencies] function and
* returning a [Set] of all the APIs it requires. These dependencies will be checked at runtime.
* It is additionally recommended to document in the comments what APIs your API depends on.
*/
abstract class API {
private var uninitializedOpMode: OpMode? by Resettable { null }

/**
* Used to access the opmode provided in [init].
*
* @throws NullPointerException If the API has not been initialized before use.
*/
protected val opMode: OpMode
get() =
uninitializedOpMode
?: throw NullPointerException("<API> has not been initialized with the OpMode before being used.")
this.uninitializedOpMode
?: throw NullPointerException("API ${this::class.simpleName} has not been initialized with the OpMode before being used.")

/**
* Equivalent to [opMode] but automatically casted to be a [LinearOpMode].
*
* @throws RuntimeException If [isLinear] is not set to true.
*/
protected val linearOpMode: LinearOpMode
get() {
if (!this.isLinear) {
throw RuntimeException(
"""
API ${this::class.simpleName} tried to access linearOpMode without setting isLinear.
Please override isLinear to true. (Currently set to ${this.isLinear}.)
""".trimIndent(),
)
}

return this.opMode as LinearOpMode
}

@Deprecated(
message = "Accessing the hardwareMap indirectly is not supported.",
Expand All @@ -28,6 +61,14 @@ abstract class API {
protected val hardwareMap: HardwareMap
get() = this.opMode.hardwareMap

/**
* Specifies whether this API requires a [LinearOpMode] to function.
*
* When true, [init] will throw an exception if it is not passed a [LinearOpMode]. Additionally,
* the API will be able to access the [linearOpMode] property without an error being thrown.
*/
open val isLinear: Boolean = false

/**
* Initializes the API to use the given [opMode].
*
Expand All @@ -39,13 +80,57 @@ abstract class API {
* API will not properly store a reference to the op-mode.
*
* @throws IllegalStateException If called more than once.
* @throws IllegalArgumentException If API requires a [LinearOpMode] but one was not passed in.
*/
open fun init(opMode: OpMode) {
// You can only initialize an API once. If it is initialized more than once, throw an error.
if (uninitializedOpMode != null) {
throw IllegalStateException("Tried to initialize an <API> more than once.")
if (this.uninitializedOpMode != null) {
val apiName = this::class.simpleName

throw IllegalStateException("Tried to initialize API $apiName more than once.")
}

// If this API requires LinearOpMode, but only a regular OpMode was passed.
if (this.isLinear && opMode !is LinearOpMode) {
val apiName = this::class.simpleName

throw IllegalArgumentException(
"""
Tried to initialized linear API $apiName without a LinearOpMode.
Please make sure that your opmode extends LinearOpMode.
Also please check that the API has not accidentally set isLinear to true.
""".trimIndent(),
)
}

// Save the opmode so it can be used by the API.
this.uninitializedOpMode = opMode

// Register this API is initialized, so dependencies can be checked.
APIDependencies.registerAPI(this)
}

/**
* A function that returns a [Set] of all other APIs it depends on to function.
*
* By default it returns an [emptySet], assuming that the API does not have any dependencies.
*
* # Example
*
* ```
* object Wheels : API() {
* fun drive(fl: Double, fr: Double, bl: Double, br: Double)
* }
*
* object SuperSlickMovement : API() {
* fun spin(power: Double) {
* Wheels.drive(power, power, power, power)
* }
*
* // SuperSliceMovement needs Wheels in order to work.
* override fun dependencies() = setOf(Wheels)
* }
* ```
*/
open fun dependencies(): Set<API> = emptySet()
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package org.firstinspires.ftc.teamcode.api.linear

import com.qualcomm.robotcore.util.Range
import org.firstinspires.ftc.teamcode.api.API
import org.firstinspires.ftc.teamcode.api.TriWheels
import org.firstinspires.ftc.teamcode.api.vision.AprilVision
import org.firstinspires.ftc.teamcode.utils.RobotConfig
Expand All @@ -13,7 +14,9 @@ import kotlin.math.sqrt
*
* Requires the [TriWheels] and [AprilVision] APIs.
*/
object AprilMovement : LinearAPI() {
object AprilMovement : API() {
override val isLinear = true

// The max speed for individual components of the movement
private const val MAX_RANGE = 0.3
private const val MAX_HEADING = 0.5
Expand Down Expand Up @@ -101,4 +104,6 @@ object AprilMovement : LinearAPI() {
// Stop the wheels from moving, the target has been reached!
TriWheels.stop()
}

override fun dependencies() = setOf(TriWheels, AprilVision)
}
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.api.linear
import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.hardware.DcMotorSimple
import com.qualcomm.robotcore.util.ElapsedTime
import org.firstinspires.ftc.teamcode.api.API
import org.firstinspires.ftc.teamcode.api.TriWheels
import org.firstinspires.ftc.teamcode.api.linear.Encoders.driveTo
import org.firstinspires.ftc.teamcode.api.linear.Encoders.spinTo
Expand All @@ -21,7 +22,9 @@ import kotlin.math.min
* @see driveTo
* @see spinTo
*/
object Encoders : LinearAPI() {
object Encoders : API() {
override val isLinear = true

private fun inchesToTick(inches: Double): Int = (RobotConfig.Encoders.TICKS_PER_INCH * inches).toInt()

private fun degreesToTick(degrees: Double): Int = (RobotConfig.Encoders.TICKS_PER_DEGREE * degrees).toInt()
Expand Down Expand Up @@ -169,6 +172,8 @@ object Encoders : LinearAPI() {
}
}

override fun dependencies() = setOf(TriWheels)

/**
* A function used by [driveTo] to figure out which two wheels are in the front, and which is
* behind.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,33 +1,21 @@
package org.firstinspires.ftc.teamcode.api.linear

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
import org.firstinspires.ftc.teamcode.api.API
import org.firstinspires.ftc.teamcode.utils.Resettable

/**
* A linear API is shared code used by linear components.
*
* It is specifically designed to only work in autonomous scenarios. It allows linear components to
* call specific methods unique to [LinearOpMode].
*
* If a linear API depends on another API, it should say so in the documentation.
*
* @see API
*/
@Deprecated(
message = "LinearAPI is deprecated. Please use the API class and override isLinear to true.",
replaceWith =
ReplaceWith(
expression = "API",
imports = arrayOf("org.firstinspires.ftc.teamcode.api.API"),
),
level = DeprecationLevel.ERROR,
)
abstract class LinearAPI {
private var uninitializedOpMode: LinearOpMode? by Resettable { null }

protected val linearOpMode: LinearOpMode
get() =
uninitializedOpMode
?: throw NullPointerException("<LinearAPI> has not been initialized with the OpMode before being used.")
get() = throw NotImplementedError()

open fun init(linearOpMode: LinearOpMode) {
// You can only initialize an API once. If it is initialized more than once, throw an error.
if (uninitializedOpMode != null) {
throw IllegalStateException("Tried to initialize a <LinearAPI> more than once.")
}

this.uninitializedOpMode = linearOpMode
throw NotImplementedError("LinearAPI is deprecated.")
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ object AprilVision : API(), VisionAPI {
/** Returns the detection data of a specific tag id, or null if not found. */
fun detect(id: Int): AprilTagDetection? = this.detections().firstOrNull { it.id == id }

override fun dependencies() = setOf(Vision)

/**
* Configures the camera's exposure and gain to be optimized for april tags.
*
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
package org.firstinspires.ftc.teamcode.utils

import android.content.Context
import com.qualcomm.ftccommon.FtcEventLoop
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.OpModeManagerNotifier
import org.firstinspires.ftc.ftccommon.external.OnCreateEventLoop
import org.firstinspires.ftc.teamcode.api.API

/**
* An object that orchestrates API dependency checking.
*/
object APIDependencies : OpModeManagerNotifier.Notifications {
/** A list of all APIs initialized for the current opmode, populated when "Init" is pressed. */
private val initializedAPIs = mutableSetOf<API>()

@OnCreateEventLoop
@JvmStatic
fun register(
@Suppress("UNUSED_PARAMETER") context: Context,
ftcEventLoop: FtcEventLoop,
) {
ftcEventLoop.opModeManager.registerListener(this)
}

override fun onOpModePreInit(opMode: OpMode) {
// Clear initialized API list when a new opmode is selected.
this.initializedAPIs.clear()
}

// Checks dependencies when the start button is pressed.
// It will only do this if debug mode is active, so as not to waste time during competitions.
override fun onOpModePreStart(opMode: OpMode) {
if (RobotConfig.debug) {
this.checkDependencies()
}
}

override fun onOpModePostStop(opMode: OpMode) {
}

/**
* Registers that an API has been initialized.
*
* You should never call this method manually. It is automatically done when `API.init` is
* called. (Which could also look like `super.init(opMode)`.)
*/
internal fun registerAPI(api: API) {
this.initializedAPIs.add(api)
}

/**
* Checks that the dependencies of initialized APIs are also initialized.
*
* @throws RuntimeException If a dependency is not initialized.
*/
private fun checkDependencies() {
// Go through every single API dependency and check if it is in the list.
for (api in this.initializedAPIs) {
for (dep in api.dependencies()) {
if (!this.initializedAPIs.contains(dep)) {
// Report the error with as much information as possible to debug the issue.
val apiName = api::class.simpleName
val depName = dep::class.simpleName

throw RuntimeException(
"""
API $apiName requires dependency $depName, but it was not initialized.
Please call $depName.init(this) in the initialization phase of the opmode.
Initialized APIs: ${this.initializedAPIs}.
""".trimIndent(),
)
}
}
}
}
}

0 comments on commit 4a6ffb0

Please sign in to comment.