Skip to content

Commit

Permalink
Minor features
Browse files Browse the repository at this point in the history
 - RobotOpMode to simplify robot use
 - Robot has more useful fields and methods
 - GamepadEx now listens to analog sticks for changes
 - Removed debug code from GUI
  • Loading branch information
amarcolini committed Jan 8, 2022
1 parent 81a7314 commit fc4da2b
Show file tree
Hide file tree
Showing 9 changed files with 91 additions and 10 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,6 @@ repositories {
maven { url 'https://jitpack.io' }
}
dependencies {
implementation "com.github.amarcolini.joos:$module:0.1.9-alpha"
implementation "com.github.amarcolini.joos:$module:0.2.0-alpha"
}
```
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
buildscript {
ext {
kotlin_version = "1.6.0"
lib_version = "v0.1.9-alpha"
lib_version = "v0.2.0-alpha"
}

repositories {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,12 +142,17 @@ open class CommandScheduler {
}

/**
* Maps a condition to commands. If the condition returns true, the commands are scheduled. A command can be mapped to multiple conditions.
* Maps a condition to commands. If the condition returns true, the commands are scheduled.
* A command can be mapped to multiple conditions.
*/
fun map(condition: BooleanSupplier, vararg commands: Command) {
conditions[condition] = commands.toMutableSet()
}

/**
* Maps a condition to commands. If the condition returns true, the commands are scheduled.
* A command can be mapped to multiple conditions.
*/
fun map(condition: BooleanSupplier, vararg commands: Runnable) {
map(condition, *commands.map { Command.of(it) }.toTypedArray())
}
Expand All @@ -156,7 +161,7 @@ open class CommandScheduler {
* Removes commands from the list of mappings.
*/
fun unmap(vararg commands: Command) {
conditions.values.forEach { it.removeAll(commands) }
conditions.values.forEach { it.removeAll(commands.toSet()) }
}

/**
Expand All @@ -174,9 +179,10 @@ open class CommandScheduler {
}

/**
* Resets this [CommandScheduler]. All commands, components, and conditions are cleared.
* Resets this [CommandScheduler]. All commands are cancelled, and all commands, components, and conditions are cleared.
*/
fun reset() {
cancelAll()
scheduledCommands.clear()
components.clear()
requirements.clear()
Expand Down
30 changes: 29 additions & 1 deletion command/src/main/kotlin/com/amarcolini/joos/command/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,37 @@ package com.amarcolini.joos.command
import com.acmerobotics.dashboard.FtcDashboard
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry
import com.amarcolini.joos.gamepad.MultipleGamepad
import com.qualcomm.robotcore.eventloop.opmode.Autonomous
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import com.qualcomm.robotcore.hardware.HardwareMap
import kotlin.reflect.full.hasAnnotation

/**
* A class that makes any command-based robot code a lot smoother
* and easier to understand.
*/
abstract class Robot(opMode: OpMode) : CommandScheduler() {
/**
* A [MultipleGamepad] storing both OpMode gamepads for convenience.
*/
@JvmField
val gamepad: MultipleGamepad = MultipleGamepad(opMode.gamepad1, opMode.gamepad2)

/**
* The hardware map obtained from the opmode.
* Whether the current OpMode is a teleop OpMode.
*/
@JvmField
val isInTeleOp: Boolean = opMode::class.hasAnnotation<TeleOp>()

/**
* Whether the current OpMode is an autonomous OpMode.
*/
@JvmField
val isInAutonomous: Boolean = opMode::class.hasAnnotation<Autonomous>()

/**
* The hardware map obtained from the OpMode.
*/
@JvmField
val hMap: HardwareMap = opMode.hardwareMap
Expand All @@ -35,4 +53,14 @@ abstract class Robot(opMode: OpMode) : CommandScheduler() {
telemetry.clear()
}, gamepad)
}

/**
* This method is runs when the current OpMode initializes.
*/
abstract fun init()

/**
* This method is run as soon as the current OpMode starts.
*/
abstract fun start()
}
36 changes: 36 additions & 0 deletions command/src/main/kotlin/com/amarcolini/joos/command/RobotOpMode.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
package com.amarcolini.joos.command

import com.qualcomm.robotcore.eventloop.opmode.*
import kotlin.reflect.full.hasAnnotation

/**
* An OpMode made for [Robot]s.
*/
abstract class RobotOpMode : OpMode() {
/**
* Whether this OpMode is a teleop OpMode.
*/
@JvmField
protected val isTeleOp = this::class.hasAnnotation<TeleOp>()

/**
* Whether this OpMode is an autonomous OpMode.
*/
@JvmField
protected val isAutonomous = this::class.hasAnnotation<Autonomous>()

private lateinit var robot: Robot
final override fun init_loop() = robot.update()
final override fun start() = robot.start()
final override fun loop() = robot.update()
override fun stop() = robot.reset()

/**
* Initializes the given robot with this OpMode. This method **must** be called
* in order for this OpMode to work correctly.
*/
protected fun initialize(robot: Robot) {
this.robot = robot
robot.init()
}
}
3 changes: 3 additions & 0 deletions command/src/main/kotlin/com/amarcolini/joos/gamepad/Button.kt
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package com.amarcolini.joos.gamepad

/**
* Represents the state of a button.
*/
class Button(
state: Boolean = false,
) : Toggleable() {
Expand Down
12 changes: 12 additions & 0 deletions command/src/main/kotlin/com/amarcolini/joos/gamepad/GamepadEx.kt
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,14 @@ class GamepadEx(gamepad: Gamepad) : Component {
@JvmField
val y: Button = Button()

private var leftStick = getLeftStick()
private var rightStick = getRightStick()
var leftStickChanged: Boolean = false
private set
@JvmName("leftStickChanged") get
var rightStickChanged: Boolean = false
private set
@JvmName("rightStickChanged") get

override fun update() {
a.update(internal.a)
Expand Down Expand Up @@ -120,6 +128,10 @@ class GamepadEx(gamepad: Gamepad) : Component {
triangle.update(internal.triangle)
x.update(internal.x)
y.update(internal.y)
leftStickChanged = getLeftStick() epsilonEquals leftStick
rightStickChanged = getRightStick() epsilonEquals rightStick
leftStick = getLeftStick()
rightStick = getRightStick()
}

fun getButton(button: GamepadButton): Toggleable = when (button) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,6 @@ internal class TrajectoryEntity(private val getScale: () -> Double) : Entity() {
val new = Vector2d(delta.x + circle.centerX, delta.y + circle.centerY)
var pos =
Vector2d(new.x.coerceIn(-72.0, 72.0), new.y.coerceIn(-72.0, 72.0))
println(pos)
val newWaypoint = when (waypoint) {
is SplineTo -> SplineTo(pos, waypoint.tangent)
is Start -> Start(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,9 +150,7 @@ abstract class ParametricCurve {
maxDepth: Int = 15,
maxDeltaK: Double = 0.01
) {
var maxReachedDepth = 0
fun parameterize(tLo: Double, tHi: Double, depth: Int) {
if (depth > maxReachedDepth) maxReachedDepth = depth
val tMid = (tLo + tHi) * 0.5
val vLo = internalGet(tLo)
val vMid = internalGet(tMid)
Expand All @@ -171,7 +169,6 @@ abstract class ParametricCurve {
}
}
parameterize(tLo, tHi, 0)
println(maxReachedDepth)
}

/**
Expand Down

0 comments on commit fc4da2b

Please sign in to comment.