Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,5 @@
.externalNativeBuild
.cxx
local.properties

/**/build
1 change: 1 addition & 0 deletions .idea/gradle.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

1 change: 0 additions & 1 deletion .idea/misc.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

4 changes: 2 additions & 2 deletions build.gradle.kts
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@ plugins {
}

allprojects {
version = property("version") as String
group = "dev.nextftc"
group = "dev.nextftc.extensions"
}

subprojects {
Expand All @@ -23,6 +22,7 @@ subprojects {
scm {
fromGithub("NextFTC", "NextFTC")
}
license("GNU General Public License, version 3", "https://www.gnu.org/licenses/gpl-3.0.html")
developer("Davis Luxenberg", "davis.luxenberg@outlook.com", url = "https://github.com/BeepBot99")
developer("Rowan McAlpin", "rowan@nextftc.dev", url = "https://rowanmcalpin.com")
developer("Zach Harel", "ftc@zharel.me", url = "https://github.com/zachwaffle4")
Expand Down
8 changes: 6 additions & 2 deletions gradle.properties
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,9 @@ kotlin.code.style=official
org.jetbrains.dokka.experimental.gradle.pluginMode=V2Enabled
org.jetbrains.dokka.experimental.gradle.pluginMode.noWarn=true

version=1.0.0
automaticMavenCentralSync=true
dev.nextftc.publishing.automaticMavenCentralSync=true

android.useAndroidX=true

versions.roadrunner=1.0.0
versions.pedro=1.0.0
7 changes: 6 additions & 1 deletion gradle/libs.versions.toml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
[versions]
kotlin = "2.0.0"
android = "8.7.3"
nextftc = "1.0.0-SNAPSHOT"
nextftc = "1.0.0-beta.2"
kotest = "5.9.1"
ftc = "10.3.0"
pedro = "2.0.0"
rr-core = "1.0.1"
rr-ftc = "0.1.25"

[libraries]
kotest-runner = { module = "io.kotest:kotest-runner-junit5", version.ref = "kotest" }
Expand All @@ -18,11 +20,14 @@ ftc-common = { group = "org.firstinspires.ftc", name = "FtcCommon", version.ref
nextftc-ftc = { group = "dev.nextftc", name = "ftc", version.ref = "nextftc" }
nextftc-hardware = { group = "dev.nextftc", name = "hardware", version.ref = "nextftc" }
pedro = { module = "com.pedropathing:ftc", version.ref = "pedro" }
rr-core = { module = "com.acmerobotics.roadrunner:core", version.ref = "rr-core" }
rr-ftc = { module = "com.acmerobotics.roadrunner:ftc", version.ref = "rr-ftc" }

[bundles]
kotest = ["kotest-runner", "kotest-assertations", "kotest-property"]
ftc = ["ftc-robot-core", "ftc-hardware", "ftc-common"]
nextftc = ["nextftc-ftc", "nextftc-hardware"]
roadrunner = ["rr-core", "rr-ftc"]

[plugins]
kotlin-jvm = { id = "org.jetbrains.kotlin.jvm", version.ref = "kotlin" }
Expand Down
8 changes: 3 additions & 5 deletions pedro/build.gradle.kts
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,13 @@ dependencies {
implementation(libs.bundles.nextftc)
implementation(libs.pedro)
compileOnly(libs.bundles.ftc)

testImplementation(libs.bundles.kotest)
testImplementation(libs.mockk)
}

version = property("versions.pedro") as String
description =
"The hardware library for NextFTC, a user-friendly library for FTC. Includes hardware interfaces, wrapper implementations, and hardware commands."
"NextFTC's extension to add support for Pedro Pathing."

nextFTCPublishing {
displayName = "NextFTC Hardware"
displayName = "NextFTC Extensions - Pedro"
logoPath = "../assets/logo-icon.svg"
}

This file was deleted.

37 changes: 37 additions & 0 deletions pedro/src/main/kotlin/dev/nextftc/extensions/pedro/FollowPath.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
package dev.nextftc.extensions.pedro

import com.pedropathing.paths.Path
import com.pedropathing.paths.PathChain
import dev.nextftc.core.commands.Command
import dev.nextftc.extensions.pedro.PedroComponent.Companion.follower

class FollowPath @JvmOverloads constructor(
private val path: PathChain,
private val holdEnd: Boolean? = null,
private val maxPower: Double? = null
) : Command() {

init {
require(maxPower == null || holdEnd != null) { "If maxPower is passed, holdEnd must be passed as well." }
}

@JvmOverloads
constructor(path: Path, holdEnd: Boolean? = null, maxPower: Double? = null) : this(
PathChain(path),
holdEnd,
maxPower
)

override val isDone: Boolean
get() = !follower.isBusy

override fun start() {
if (holdEnd !== null && maxPower !== null) follower.followPath(path, maxPower, holdEnd)
else if (holdEnd !== null) follower.followPath(path, holdEnd)
else follower.followPath(path)
}

override fun stop(interrupted: Boolean) {
if (interrupted) follower.breakFollowing()
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
package dev.nextftc.extensions.pedro

import com.pedropathing.follower.Follower
import com.qualcomm.robotcore.hardware.HardwareMap
import dev.nextftc.core.components.Component
import dev.nextftc.core.units.Angle
import dev.nextftc.core.units.rad
import dev.nextftc.ftc.ActiveOpMode
import java.util.function.Supplier

class PedroComponent(private val followerFactory: (HardwareMap) -> Follower) : Component {

override fun preInit() {
_follower = followerFactory(ActiveOpMode.hardwareMap)
}

override fun preWaitForStart() = follower.update()
override fun preUpdate() = follower.update()

override fun postStop() {
_follower = null
}

companion object {
private var _follower: Follower? = null

@get:JvmName("follower")
@JvmStatic
val follower: Follower
get() = _follower ?: error("Follower not initialized! Make sure you added PedroComponent to your OpMode.")

@get:JvmName("gyro")
@JvmStatic
val gyro: Supplier<Angle> = Supplier { follower.totalHeading.rad.normalized }

}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
package dev.nextftc.extensions.pedro

import dev.nextftc.extensions.pedro.PedroComponent.Companion.follower
import dev.nextftc.hardware.driving.DriverControlledCommand
import java.util.function.Supplier

class PedroDriverControlled @JvmOverloads constructor(
drivePower: Supplier<Double>,
strafePower: Supplier<Double>,
turnPower: Supplier<Double>,
private val robotCentric: Boolean = true
) : DriverControlledCommand(drivePower, strafePower, turnPower) {

override fun start() {
follower.startTeleopDrive()
}

override fun calculateAndSetPowers(powers: DoubleArray) {
val (drive, strafe, turn) = powers
follower.setTeleOpDrive(drive, strafe, turn, robotCentric)
}

override fun stop(interrupted: Boolean) {
if (interrupted) follower.breakFollowing()
}
}
20 changes: 20 additions & 0 deletions pedro/src/main/kotlin/dev/nextftc/extensions/pedro/TurnBy.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
package dev.nextftc.extensions.pedro

import dev.nextftc.core.commands.Command
import dev.nextftc.core.units.Angle
import dev.nextftc.core.units.abs
import dev.nextftc.extensions.pedro.PedroComponent.Companion.follower

class TurnBy(private val angle: Angle) : Command() {

init {
named("TurnBy($angle)")
}

override val isDone: Boolean
get() = !follower.isTurning

override fun start() {
follower.turn(abs(angle).inRad, angle.sign > 0)
}
}
19 changes: 19 additions & 0 deletions pedro/src/main/kotlin/dev/nextftc/extensions/pedro/TurnTo.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package dev.nextftc.extensions.pedro

import dev.nextftc.core.commands.Command
import dev.nextftc.core.units.Angle
import dev.nextftc.extensions.pedro.PedroComponent.Companion.follower

class TurnTo(private val angle: Angle) : Command() {

init {
named("TurnTo($angle)")
}

override val isDone: Boolean
get() = !follower.isTurning

override fun start() {
follower.turnTo(angle.inRad)
}
}
17 changes: 0 additions & 17 deletions pedro/src/test/java/dev/nextftc/extensions/ExampleUnitTest.kt

This file was deleted.

42 changes: 42 additions & 0 deletions roadrunner/build.gradle.kts
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
plugins {
kotlin("android")
id("com.android.library")
}

android {
namespace = "dev.nextftc.extensions.roadrunner"
compileSdk = 35

defaultConfig {
minSdk = 24
}

compileOptions {
sourceCompatibility = JavaVersion.VERSION_1_8
targetCompatibility = JavaVersion.VERSION_1_8
}

kotlinOptions {
jvmTarget = "1.8"
freeCompilerArgs += "-Xjvm-default=all"
}

publishing {
singleVariant("release")
}
}

dependencies {
implementation(libs.bundles.nextftc)
implementation(libs.bundles.roadrunner)
implementation(libs.bundles.ftc)
}

description =
"Support for using RoadRunner with NextFTC."

nextFTCPublishing {
displayName = "NextFTC Extensions - RoadRunner"
logoPath = "../assets/logo-icon.svg"
version = property("versions.roadrunner") as String
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
package dev.nextftc.extensions.roadrunner

import com.acmerobotics.roadrunner.Pose2dDual
import com.acmerobotics.roadrunner.PoseVelocity2d
import com.acmerobotics.roadrunner.Time
import com.acmerobotics.roadrunner.TimeTrajectory
import com.acmerobotics.roadrunner.Trajectory
import com.acmerobotics.roadrunner.Vector2d
import com.qualcomm.robotcore.util.ElapsedTime
import dev.nextftc.core.commands.Command

/**
* Follows a trajectory parametrized by time.
*
* Note that the output of [TrajectoryCommandBuilder.build] only returns a [Command]
* object and not a [FollowTrajectory] object,
* because the builder sequences the trajectory with other actions,
* such as [Turn]s, [dev.nextftc.core.commands.delays.Delay]s or user-specified callbacks.
*/
class FollowTrajectory(private val mecanumDrive: NextFTCMecanumDrive, private val trajectory: TimeTrajectory) : Command() {
constructor(mecanumDrive: NextFTCMecanumDrive, trajectory: Trajectory) :
this(mecanumDrive, TimeTrajectory(trajectory))

val timer = ElapsedTime()

override val isDone: Boolean
get() = timer.seconds() >= trajectory.duration

override fun start() {
timer.reset()
}

override fun update() {
val txWorldTarget: Pose2dDual<Time> = trajectory[timer.seconds()]

val robotVelRobot: PoseVelocity2d = mecanumDrive.updatePoseEstimate()

val command =
mecanumDrive.controller.compute(txWorldTarget, mecanumDrive.getPose(), robotVelRobot)

mecanumDrive.setDrivePowersFF(command)
}

override fun stop(interrupted: Boolean) {
mecanumDrive.setDrivePowersFF(PoseVelocity2d(Vector2d(0.0, 0.0), 0.0))
}
}
Loading
Loading