@@ -5,6 +5,9 @@ import com.acmerobotics.roadrunner.Pose2d
55import com.acmerobotics.roadrunner.PoseVelocity2d
66import com.acmerobotics.roadrunner.PoseVelocity2dDual
77import com.acmerobotics.roadrunner.Time
8+ import com.acmerobotics.roadrunner.Vector2d
9+ import dev.nextftc.core.commands.utility.LambdaCommand
10+ import java.util.function.Supplier
811
912/* *
1013 * Represents a RoadRunner Mecanum drivetrain from the QuickStart.
@@ -26,4 +29,31 @@ abstract class NextFTCMecanumDrive {
2629 abstract fun commandBuilder (beginPose : Pose2d ): TrajectoryCommandBuilder
2730
2831 open fun commandBuilder () = commandBuilder(getPose())
32+
33+ /* *
34+ * Creates a command for driver-controlled operation.
35+ *
36+ * @param xPower A function providing the x-axis power.
37+ * @param yPower A function providing the y-axis power.
38+ * @param headingPower A function providing the heading power.
39+ * @param robotCentric Whether the controls are robot-centric (default: true).
40+ * @return A [LambdaCommand] that updates the drivetrain powers.
41+ */
42+ @JvmOverloads fun driverControlledCommand (
43+ xPower : Supplier <Double >,
44+ yPower : Supplier <Double >,
45+ headingPower : Supplier <Double >,
46+ robotCentric : Boolean = true
47+ ) = LambdaCommand ()
48+ .setUpdate {
49+ var transVel = Vector2d (xPower.get(), yPower.get())
50+
51+ if (! robotCentric) {
52+ transVel = getPose().heading * transVel
53+ }
54+
55+ setDrivePowers(PoseVelocity2d (transVel, headingPower.get()))
56+ }.setIsDone { false }
57+ .requires(this )
58+ .named(" RoadRunner Driver Controlled" )
2959}
0 commit comments