Introduction
Welcome to the Expressway docs! This site will house examples and documentation of various features found within Expressway and Roadrunner itself!
Expressway can be found here, and installation instructions can be found here.
We also have a Discord server where you can ask questions and get help with Expressway and RoadRunner.
What is Expressway?
Expressway is a library built on top of RoadRunner that provides a more flexible and powerful way to create actions. Actions, introduced in RoadRunner 1.0, are a way to create reusable and composable pieces of robot code. Expressway builds on this concept by providing a way to create more complex actions that can be used in a variety of situations.
Actions help you define simple behaviors that are easy to combine into large routines. By breaking down autonomous programs you make them easier to understandand and modify. And then the base actions can be reused in new autonomous programs so you never need to start from scratch. But most importantly of all your code will play nice with the Road Runner Quickstart. Let’s see how this all works!
- RoadRunner Documentation
Actions are very similar to commands as implemented in libraries like WPILib and FTCLib. Road Runner uses a different name for this pattern to distinguish its particular design from these peer libraries. The ideas have also been explored extensively outside the FIRST realm. Check out cooperative multitasking and coroutines if you’re interested.
In addition to our additions to the action system, Expressway also provides a number of other features, including converters for geometry classes, and a PIDF controller.
Kotlin?
Expressway is written in Kotlin, a modern language that is fully interoperable with Java. This means that you can use both Java and Kotlin code in the same project. For the most part, the code examples in this documentation will be in Kotlin, but Java versions of the same code will be provided when necessary.
More information about Kotlin can be found here, and this Cookbook article explains some of its benefits and usage in FTC.
Installing Expressway
Repositories
Ensure this block is in the "repositories" block of your TeamCode module build.gradle. If you use any Dairy libraries, this will already be present, so you do not have to add it twice.
maven {
url = 'https://repo.dairy.foundation/releases'
}
Dependencies
Add the following lines to the "dependencies" block of that same build.gradle:
implementation "page.j5155.roadrunner.expressway:core:0.3.7"
implementation "page.j5155.roadrunner.expressway:ftc:0.3.7"
You must do a Gradle Sync after adding these lines to your build.gradle file so that Android Studio can download the necessary files.
Updating Expressway
To update Expressway, change the version number in the dependencies block of your build.gradle file to the latest version.
New Base Actions
Expressway comes with two new base action types: InitLoopAction
and InitLoopCondAction
(aka ILCAction
).
These can be used for anything a regular Action
can be used for, but they are easier to read and write.
While InitLoopAction
and InitLoopCondAction
are both more verbose than the base Action
,
they are easier to read and write, and can be more powerful in some situations.
Expressway provides these two new base actions to make it easier to write complex actions,
but you can still use the base Action
if you prefer.
When creating actions, you should choose the one that best fits your needs.
InitLoopAction
InitLoopAction
is an Action
with two methods: init
and loop: Boolean
.
init
is called once when the action is first started,
and loop
is what is called when the action is running
(we will discuss ways to run your Actions later).
Just like the base Action
, loop
should return true
if the action needs to be continued,
and false
if it is done.
Here is an example of an InitLoopAction
that moves a motor to a position
using Expressway's PIDF Controller (more information about what it does and how it works
are in PIDF Controller):
class PIDAction(private val motor: DcMotor, target: Int, private val controller: PIDFController) : InitLoopAction() {
var target = target
set(value) {
pidf.targetPosition = value
field = value
}
override fun init() {
pidf.setTargetPosition(target)
}
override fun loop(p: TelemetryPacket): Boolean {
val position: Int = motor.getCurrentPosition()
val power: Double = pidf.update(position.toDouble())
p.put("Motor Info", "Target: " + target + "; Error " + (target - position) + "; Power: " + power)
motor.setPower(power)
return position < (target - 50) || position > (target + 50)
}
}
In this example, init
sets the target position of the PIDF controller,
and loop
uses the PIDF controller to calculate what the motor's power should be, and sets that power appropriately.
Note that just like a regular Action
, loop
should return true
if the action is not done, and false
if it is.
In the case of this action, it will return true
until the motor is within 50 encoder ticks of the target position.
In addition, just like with the base Action
, there is a TelemetryPacket p
that is passed as an argument to the loop
method.
This allows you to add telemetry to your action, which is sent to FTCDashboard and can help in debugging.
When declaring the target
variable, we specify that its set
function
(called in Kotlin by saying <object>.target = value
or in Java with <object>.setTarget(value)
)
will also update the targetPosition
field of the PIDF controller.
This allows us to change the target position of the action before it completes, which may be useful in some cases.
Here is a Java version of the same action:
class PIDFAction extends InitLoopAction {
private final DcMotor motor;
private final PIDFController pidf;
private int target;
public PIDFAction(DcMotor motor, int target, PIDFController controller) {
this.motor = motor;
this.pidf = controller;
this.target = target;
this.pidf.setTargetPosition(target);
}
public void setTarget(int value) {
this.pidf.setTargetPosition(value);
this.target = value;
}
@Override
public void init() {
pidf.setTargetPosition(target);
}
@Override
public boolean loop(TelemetryPacket p) {
int position = motor.getCurrentPosition();
double power = pidf.update((double) position);
p.put("Motor Info", "Target: " + target + "; Error " + (target - position) + "; Power: " + power);
motor.setPower(power);
return position < (target - 50) || position > (target + 50);
}
}
InitLoopCondAction
Similarly to the InitLoopAction
, the InitLoopCondAction
is an Action
with two methods: init
and loop
.
However, the constructor of the InitLoopCondAction
takes a Condition
,
an interface with a single method invoke: Boolean
.
Every time the action is run, it will check condition
and stop if it returns false.
The condition
is essentially what the return statement of the loop
method would be in a regular InitLoopAction
.
One benefit of this (aside from the fact that it is easier to read and write)
is that you can access the isRunning
property to check if the action is running (i.e. condition
is false).
You can also access the condition
function from the Action
object
with <object>.condition
(or <object>.getCondition()
in Java).
Because condition
is a function, to call it you need parentheses, like <object>.condition()
.
Note that in Java you must call the get
function explicitly, like <object>.condition.get()
,
The reason for this is explained in the example below.
The other benefit of InitLoopCondAction
is the ability to define an explicit cleanup
method.
The cleanup
method is called when the action is done,
and can be used to reset any variables or states that the action may have changed.
Here is an example of an InitLoopCondAction
using the same PIDF controller as before:
}
fun hasArrived(motor: DcMotor, target: Int) : Condition {
return { motor.currentPosition !in (target - 50)..(target + 50) }
}
class PIDFActionEx(
private val motor: DcMotor, target: Int, private val controller: PIDFController)
: InitLoopCondAction(hasArrived(motor, target)) {
var target = target
set(value) {
pidf.targetPosition = value
field = value
}
override fun init() {
pidf.setTargetPosition(target)
}
override fun loop(p: TelemetryPacket) {
val position = motor.currentPosition
val power = pidf.update(position.toDouble())
p.put("Motor Info", "Target: $target; Error ${target-position}; Power: $power")
motor.power = power
}
}
In this situation, we define a function hasArrived(motor: DcMotor, target: Int): Condition
that returns true if the motor is within 50 encoder ticks of the target position.
The return type Condition
indicates that we are actually returning a function1,
and not whether the motor has arrived or not at the time hasArrived
is called.
This is because we want to check if the motor has arrived every time the action is run, not just when it is first instantiated.
When defining hasArrived
, we use {}
to specify that we are defining a function to return, and not returning the Boolean value of the expression inside the braces.
When creating the InitLoopCondAction
, we pass hasArrived
into the superclass constructor,
which is the constructor of the InitLoopCondAction
class.
We can also see that the init
method is the same as before,
and the loop
method is almost the same as before, but it does not return any value.
Lastly, instead of defining hasArrived
as a separate function, we could define it as an anonymous function in the constructor of the InitLoopCondAction
:
class PIDFActionEx(
private val motor: DcMotor, target: Int, coefficients: PIDFController.PIDCoefficients, )
: InitLoopCondAction( { motor.currentPosition !in (target - 50)..(target + 50) }) {
This is useful if you only need to use the function once, and do not want to define it elsewhere in your code.
Remember that if you create a PIDFActionEx
object called action
, you can access the condition
function with action.condition
,
and you can call it with action.condition()
.
Here is a Java version of the same action:
public class PIDFActionEx extends InitLoopCondAction {
private final DcMotor motor;
private final PIDFController controller;
private int target;
public PIDFActionEx(DcMotor motor, int target, PIDFController controller) {
super(hasArrived(motor, target));
this.motor = motor;
this.controller = controller;
this.target = target;
this.pidf.setTargetPosition(target);
}
private static Condition hasArrived(DcMotor motor, int target) {
return () -> motor.getCurrentPosition() <= (target - 50) || motor.getCurrentPosition() >= (target + 50);
}
public void setTarget(int value) {
this.pidf.setTargetPosition(value);
this.target = value;
}
@Override
public void init() {
pidf.setTargetPosition(target);
}
@Override
public void loop(TelemetryPacket p) {
int position = motor.getCurrentPosition();
double power = pidf.update((double) position);
p.put("Motor Info", "Target: " + target + "; Error " + (target - position) + "; Power: " + power);
motor.setPower(power);
}
}
Note that in Java we must specifically define hasArrived
as returning a Condition
object.
This is because Java does not automatically convert a lambda1 function to an interface with a single method
(also known as a functional interface) like Kotlin does.
Just like before, though, we can define hasArrived
as an anonymous function in the constructor of the InitLoopCondAction
:
public class PIDFActionEx extends InitLoopCondAction {
public PIDFActionEx(DcMotor motor, int target, PIDFController.PIDCoefficients coefficients) {
super(() -> motor.getCurrentPosition() <= target - 50 || motor.getCurrentPosition() >= target + 50);
//rest of the constructor
}
}
Kotlin will convert hasArrived
to a Condition
object automatically,
which is why we can pass it directly into the InitLoopCondAction
constructor.
This is similar to how Java converts 0
to a double
when you pass it into a method that takes a double
parameter.
A lambda function is a function that is not defined by name, but rather by its parameters and return type.
For example, val add = { a: Int, b: Int -> a + b }
is a lambda function that takes two Int
s and returns their sum.
The contents of hasArrived
in both the Kotlin and Java examples actually return a lambda function,
which is why it works as a Condition
object in Kotlin.
Lambda functions and functional interfaces go hand-in-hand,
as lambda functions are often used to define the single method in a functional interface,
like the variant constructors of PIDFActionEx
in both Kotlin and Java.
Action Wrappers
Action Wrappers are a way to create actions that wrap around other actions.
Two examples of this are SequentialAction
and ParallelAction
, present in RoadRunner itself.
These actions allow you to run multiple actions in sequence or in parallel, respectively.
In Expressway, we have a few more action wrappers that you can use to create more complex actions.
RaceParallelAction
RaceParallelAction
is an action that runs multiple actions in parallel,
but stops when the first action finishes.
ConditionalAction
ConditionalAction
is an action that runs one of two actions based on a condition or determinant
.
The determinant
is a function that returns a Boolean, and the action will run trueAction
if determinant
returns true,
and falseAction
otherwise.
Here is an example ConditionalAction
:
fun choose(): Action {
return ConditionalAction(
SleepAction(1.0), // will be run if the conditional is true
SleepAction(2.0) // will be run if the conditional is false
) { Math.random() > 0.5 } // lambda conditional function, returning either true or false;
// this example picks which one to run randomly
}
In this example, choose
returns a ConditionalAction
that runs a SleepAction
with a duration of 1 second if the random number is greater than 0.5,
and a SleepAction
with a duration of 2 seconds otherwise.
Here is a Java version of the same action:
public Action choose() {
return new ConditionalAction(
new SleepAction(1.0), // will be run if the conditional is true
new SleepAction(2.0), // will be run if the conditional is false
() -> Math.random() > 0.5 // lambda conditional function, returning either true or false;
// this example picks which one to run randomly
);
}
TimeoutAction
TimeoutAction is an action that runs another action, but forcibly stops it after a certain amount of time. This is useful if you want to ensure that an action does not run for too long.
However, it is important to ensure that the force stop does not cause any issues with the robot.
Here is an example TimeoutAction
:
fun timeout(): Action {
return TimeoutAction(
SleepAction(5.0), // the action to run
3.0 // the timeout in seconds
)
}
Action Runner
If you've used RoadRunner's Action system, you're probably familiar with Actions.runBlocking
.
runBlocking is, well, blocking: it runs its argument until its done, blocking any other code from running.
This is usually fine for autonomous, but in teleop, you are often using a loop.
Since runBlocking blocks the loop, you can't receive other inputs while an action is running.
The teleop actions section of the RoadRunner docs explain how to run actions during the teleop loop, but it's a bit complicated.
Expressway simplifies this process with the ActionRunner
class.
What is ActionRunner?
ActionRunner
is a class that allows you to run actions asynchronously.
There are actually three variants of ActionRunner
: ActionRunner
itself,
its superclass NoPreviewActionRunner
, and UniqueActionRunner
.
ActionRunner
is the most basic of the three, and is the one you will use most often.NoPreviewActionRunner
is a superclass ofActionRunner
whose constructor requests a function that takes in aTelemetryPacket
object and returns nothing (Unit
).ActionRunner
's constructor has no parameters, as it passes FTC Dashboard'ssendTelemetryPacket
function to its super constructor.
UniqueActionRunner
is a subclass ofActionRunner
that checks if the action is already present in the queue before adding it.- This is useful if you want to prevent the same action from running multiple times.
How do I use it?
To use ActionRunner
, you first need to create an instance of it. This must be done in the init
method of your OpMode.
In Kotlin, you can use by lazy
to create the instance lazily, like so:
class MyOpMode : OpMode() {
private val actionRunner by lazy { ActionRunner() }
override fun init() {
//do something
}
override fun loop() {
//do something
}
}
In Java, you can create the instance in the init
method:
public class MyOpMode extends OpMode {
private ActionRunner actionRunner;
@Override
public void init() {
actionRunner = new ActionRunner();
}
@Override
public void loop() {
//do something
}
}
Once you have an instance of ActionRunner
, you can add actions to it using the runAsync
method.
runAsync
takes in an Action
object and adds it to the queue to be run asynchronously.
Finally, you need to call updateAsync
in your loop method to run the actions.
Here is an example of how you might use ActionRunner
in an OpMode. Assume you've already created a
Claw class with two methods, open
and close
, that returns Actions that open and close the claw, respectively,
and an Arm class with a method createPidfAction
that returns a PIDFActionEx
object defined
in the Creating Actions section.
class MyOpMode : OpMode() {
private val actionRunner by lazy { ActionRunner() }
private val claw by lazy { Claw() }
private val arm by lazy { Arm() }
private val pidfAction by lazy { arm.createPidfAction() }
override fun init() {
actionRunner.runAsync(claw.open()) //ensure that the claw opens once we start using runAsync
pidfAction.target = 0 //set the initial target position to 0
actionRunner.runAsync(pidfAction) //ensure that the arm moves to position 0 when we start using runAsync
}
override fun loop() {
if (gamepad1.a) {
actionRunner.runAsync(claw.close())
} else if (gamepad1.b) {
actionRunner.runAsync(claw.open())
}
if (gamepad1.dpad_up) {
pidfAction.target = 100
if (pidfAction.condition.invoke()) { //check to see if the arm has arrived at its target
actionRunner.runAsync(pidfAction) //if it had completed, it was removed from the queue, so we need to add it back
}
} else if (gamepad1.dpad_down) {
pidfAction.target = 0
if (pidfAction.condition.invoke()) { //check to see if the arm has arrived at its target
actionRunner.runAsync(pidfAction) //if it had completed, it was removed from the queue, so we need to add it back
}
}
actionRunner.updateAsync() //update each action
}
}
Action OpModes
Expressway comes with two new OpMode types: ActionOpMode
and ActionLinearOpMode
,
which can be used instead of the default OpMode and LinearOpMode, respectively.
ActionOpMode
At its core, ActionOpMode
is simply an OpMode
with an runner
object called runner
.
This allows you to run actions asynchronously in the loop
method of your OpMode,
using the instructions in the Action Runner section.
Here is an example of how you might use ActionOpMode
in your code. Assume you've already created a
Claw class with two methods, open
and close
, that returns Actions that open and close the claw, respectively,
and an Arm class with a method createPidfAction
that returns a PIDFActionEx
object defined
in the Creating Actions section.
class MyOpMode : ActionOpMode() {
private val claw by lazy { Claw() }
private val arm by lazy { Arm() }
private val pidfAction by lazy { arm.createPidfAction() }
override fun init() {
runner.runAsync(claw.open()) //ensure that the claw opens once we start using runAsync
pidfAction.target = 0 //set the initial target position to 0
runner.runAsync(pidfAction) //ensure that the arm moves to position 0 when we start using runAsync
}
override fun loop() {
if (gamepad1.a) {
runner.runAsync(claw.close())
} else if (gamepad1.b) {
runner.runAsync(claw.open())
}
if (gamepad1.dpad_up) {
pidfAction.target = 100
if (pidfAction.condition.invoke()) { //check to see if the arm has arrived at its target
runner.runAsync(pidfAction) //if it had completed, it was removed from the queue, so we need to add it back
}
} else if (gamepad1.dpad_down) {
pidfAction.target = 0
if (pidfAction.condition.invoke()) { //check to see if the arm has arrived at its target
runner.runAsync(pidfAction) //if it had completed, it was removed from the queue, so we need to add it back
}
}
runner.updateAsync() //update each action
}
}
ActionLinearOpMode
(WIP)
PID-To-Point Action
The PIDToPoint
class is an action that uses the SquID Controller
to move a drivetrain to a specified point.
It is designed to work with RoadRunner's MecanumDrive
class,
present in the roadrunner-quickstart
repository.
The PIDToPoint action has not been tested in a real-world scenario, so it may not work as expected. If you encounter any issues, please let us know by creating an issue on the Expressway GitHub repository, or by contacting us on our Discord server.
Constructing PIDToPoint
The PIDToPoint
constructor is the following:
private val pose: Supplier<Pose2d>,
private val vel: Supplier<PoseVelocity2d>,
private val target: Pose2d,
private val powerUpdater: Consumer<PoseVelocity2d>,
axialCoefs: PIDFController.PIDCoefficients,
lateralCoefs: PIDFController.PIDCoefficients,
headingCoefs: PIDFController.PIDCoefficients,
A lot, right? Let's break it down.
Pose
and Vel
The pose
and vel
suppliers are functions that return the current pose and velocity of the robot, respectively.
The reason they are suppliers is that the pose and velocity of the robot change over time,
and we need to get the current pose and velocity every time the action is updated.
They are designed to work with RoadRunner's MecanumDrive
class, present in the roadrunner-quickstart
repository.
However, in order to update the pose
variable of the MecanumDrive
class, you need to call the updatePoseEstimate
method,
so we recommend creating a function in your MecanumDrive
class (or any subclass of it) called getPose
that updates the pose estimate and returns the pose.
public Pose2d getPoseEstiamte() {
updatePoseEstimate();
return pose;
}
Target
The target
is the point that the robot is moving to.
PowerUpdater
The powerUpdater
consumer is a function that sets the power of the drivetrain motors based on the output of the Squid Controller.
It is designed to work with MecanumDrive.setDrivePowers
, present in the roadrunner-quickstart
repository.
Coefficients
The axialCoefs
, lateralCoefs
, and headingCoefs
are the PID coefficients for the Squid Controller,
discussed in the PID Controller section.
Conveniently, the values for your coefficients are actually tuned during the RoadRunner tuning process.
Because most of these parameters are obtained from the MecanumDrive
class,
we recommend creating a function in your MecanumDrive
class (or any subclass of it)
that returns a PIDToPoint
action object with the correct parameters.
Implementing PIDToPoint
Here is how you could create a function to return a PIDToPoint
object in your MecanumDrive
class.
public PIDToPoint pidToPointAction(Pose2d target) {
return new PIDToPoint(
(this::getPoseEstimate)
(this::updatePoseEstimate) // updatePoseEstimate, in addition to updating the pose property, returns the velocity of the robot
target, // the target pose
(this::setDrivePowers), // setDrivePowers uses inverse kinematics to set the powers of the drivetrain motors
new PIDFController.PIDCoefficients(PARAMS.axialGain, 0, PARAMS.axialVelGain), // the axial PID coefficients
new PIDFController.PIDCoefficients(PARAMS.lateralGain, 0, PARAMS.lateralVelGain), // the lateral PID coefficients
new PIDFController.PIDCoefficients(PARAMS.headingGain, 0, PARAMS.headingVelGain) // the heading PID coefficients
);
}
Or in Kotlin (even though the RoadRunner quickstart is in Java, you can put Kotlin code in your project):
fun pidfToPointAction(target: Pose2d): PIDToPoint = PIDToPoint(
this::getPoseEstimate,
this::linearVel,
target,
this::setDrivePowers,
PIDFController.PIDCoefficients(RR_PARAMS.axialGain, 0.0, RR_PARAMS.axialVelGain), // the axial PID coefficients
PIDFController.PIDCoefficients(RR_PARAMS.lateralGain, 0.0, RR_PARAMS.lateralVelGain), // the lateral PID coefficients
PIDFController.PIDCoefficients(RR_PARAMS.headingGain, 0.0, RR_PARAMS.headingVelGain) // the heading PID coefficients
)
The ::
operator in both Java and Kotlin can be used to reference a method or function,
so if a class method has the same signature as a function type (like Supplier
or Consumer
),
you can use the ::
operator to reference the method.
In Kotlin, you can also use the ::
operator to reference a top-level function, or a class property.
For example, the updatePoseEstimate
method in the MecanumDrive
class has the same signature as a Supplier<Pose2d>
,
so you can use this::updatePoseEstimate
to reference the method and pass it to the PIDToPoint
constructor.
Alternatively, since other Action types are classes,
you could create a PIDToPointAction class that extends the PIDToPoint class
as a subclass of MecanumDrive
that simply calls the constructor of the superclass with the correct parameters.
class PIDToPointAction(target: Pose2d) : PIDToPoint(
this::getPoseEstimate,
this::linearVel,
target,
this::setDrivePowers,
new PIDFController.PIDCoefficients(PARAMS.axialGain, 0, PARAMS.axialVelGain),
new PIDFController.PIDCoefficients(PARAMS.lateralGain, 0, PARAMS.lateralVelGain),
new PIDFController.PIDCoefficients(PARAMS.headingGain, 0, PARAMS.headingVelGain)
)
Using PIDToPoint
Let's assume you added the pidToPointAction
function to your MecanumDrive
class.
Here is an example of how you might use the PIDToPoint
action in an OpMode:
class MyOpMode : ActionOpMode {
private val drive by lazy { MecanumDrive(hardwareMap, Pose2d(0.0, 0.0, 0.0)) }
private val target = Pose2d(24.0, 24.0, 0.0)
private val action = drive.pidToPointAction(target)
override fun init() {
drive.updatePoseEstimate()
}
override fun start() {
runner.runAction(action)
}
override fun loop() {
runner.updateAsync()
}
}
In this example, the robot will move to the point (24, 24, 0) until it reaches the target.
runAsync is only called during start
so that the robot does not move during initialization.
The updateAsync
method is called every loop to update the action.
PIDF Controller
The PIDF Controller is a controller that uses a PIDF algorithm to control a motor's positionn. It is actually a port of the PIDF Controller present in RoadRunner 0.5, so if you're familiar with that, you should be able to use this controller with ease.
What is PIDF?
PIDF stands for Proportional, Integral, Derivative, and Feedforward. It is a control loop feedback mechanism widely used in industrial control systems. The PIDF controller calculates an error value as the difference between a desired setpoint (target) and a measured process variable (actual value - in FTC, a motor position). The controller attempts to minimize the error by calculating a power value to apply to the motor.
For more information, see CtrlAltFtc, a website commonly referenced for control theory in FTC.
How do I use it?
To use the PIDF Controller, you first need to create an instance of it.
There are a few constructor options for it,
but the most basic one is PIDFController(coefficients: PIDCoefficients)
.
This constructor takes in a PIDCoefficients
object, which is a data class
with three double parameters: kp
, ki
, and kd
.
Here is an example of how you might use the PIDF Controller in an OpMode:
class MyOpMode : OpMode {
private val motor by lazy { hardwareMap.get(DcMotorEx::class.java, "motor") } }
private val pidfController by lazy { PIDFController(PIDCoefficients(1.0, 0.0, 0.0)) }
//the coefficients are just placeholders, you should tune them to your motor
override fun init() {
pidfController.targetPosition = 1000 //set the target position to 1000
}
override fun loop() {
motor.power = pidfController.update(motor.currentPosition)
//update the motor power based on the current position *every loop*
}
}
Feedforward
The other constructors for PIDFController allow you to specify feedforward coefficients. Feedforward is a control strategy that uses a model of the system to predict the output of the system.
There are three feedforward coefficients and a feedforward function: kV
, kA
, kStatic
, and kF
.
kV
is the velocity feedforward coefficient.kA
is the acceleration feedforward coefficient.kStatic
is the additive feedforward constant.kF
is a custom feedforward function of typeFeedforwardFun
.FeedforwardFun
is an interface with a single methodcompute(position: Double, velocity: Double?): Double
.
When creating a PIDFController object, you can specify all of those, just kV
, kA
and kStatic
, or just kF
.
Here is an example of how you might use the PIDF Controller with feedforward in an OpMode:
class MyOpMode : OpMode {
private val motor by lazy { hardwareMap.get(DcMotorEx::class.java, "motor") } }
private val pidfController by lazy { PIDFController(PIDCoefficients(1.0, 0.0, 0.0), 0.1, 0.1, 0.1) }
//the coefficients are just placeholders, you should tune them to your motor
override fun init() {
pidfController.targetPosition = 1000 //set the target position to 1000
}
override fun loop() {
motor.power = pidfController.update(System.nanoTime(), motor.currentPosition, motor.velocity)
//when specifing velocity, you must also specify the time in nanoseconds
//update the motor power based on the current position and velocity *every loop*
}
}
Using the PIDFController with Actions can be found in the Base Actions section.
Tuning
Tuning the PIDF Controller is a process of adjusting the coefficients to get the desired behavior. There are many resources online that can help you with this, including the CtrlAltFtc website mentioned earlier.
To make tuning easier, all of the PIDFController parameters
are public var
s so you can change them after object creation.
This article will not go into detail about tuning the PIDF Controller, but here is a brief overview of the effects of increasing the basic PID coefficients on the system:
Effects of increasing coefficients on the system:
Parameter | Rise Time | Overshoot | Settling Time | Steady-State Error | Stability |
---|---|---|---|---|---|
kP | Decrease | Increase | Small Change | Decrease | Decrease |
kI | Decrease | Increase | Increase | Eliminate | Decrease |
kD | Small Change | Decrease | Decrease | No Change | Increase |
Table sourced from Wikipedia.
Squid Controller
The Squid Controller is a variant of the PIDF Controller that square roots the output. The reason for this is the simple kinematic equation \({v_f}^2 = {v_i}^2 + 2ad \), where \(v_f\) is the final velocity, \(v_i\) is the initial velocity, \(a\) is the acceleration, and \(d\) is the displacement.
If we take the square root of both sides, we get \(v_f = \sqrt{{v_i}^2 + 2ad} \), which is the equation for the final velocity. Note that in a PID controller, we are minimizing the error by incorporating the position, velocity, and acceleration, which are the three terms in the equation above.
Since setting motor power effectively sets velocity1, the output of the Squid Controller will be more kinematically accurate than the output of the PIDF Controller.
Another benefit of the Squid Controller is that it is nonlinear, which means that it can be more accurate than a linear controller in some cases. For example, a linear controller might not be able to accurately control a motor at low speeds, but a Squid Controller can.
Using SquidController
Using the SquidController
is very similar to using the PIDFController
.
You can create an instance of it with the same constructor as the PIDFController
,
and the update
method works the same way as the update
method in the PIDFController
.
Here is an example of how you might use the SquidController
in an OpMode:
class MyOpMode : OpMode {
private val motor by lazy { hardwareMap.get(DcMotorEx::class.java, "motor") }
private val squidController by lazy { SquidController(PIDCoefficients(1.0, 0.0, 0.0)) }
//the coefficients are just placeholders, you should tune them to your motor
override fun init() {
squidController.targetPosition = 1000 //set the target position to 1000
}
override fun loop() {
motor.power = squidController.update(motor.currentPosition)
//update the motor power based on the current position *every loop*
}
}
Actions that use the SquidController
could thus be built in the same way as actions that use the PIDFController
;
since the SquidController
is a subclass of the PIDFController
,
you can actually pass a SquidController
object into an action that expects a PIDFController
,
such as the PIDFAction
and PIDFActionEx
from the Base Actions section.
There is also a setVelocity
method in the DcMotorEx
class,
which runs an internal velocity PID controller, but it isn't recommended
because the internal controller runs at a much lower frequency than the vast majority of OpMode loops.
Functions as Parameters
While this section is not necessary to understand Expressway, the concepts of higher order functions are useful to know about.
In a lot of Expressway's code, you might notice that a lot of classes and functions take parameters of type Supplier
.
Supplier<T>
is a functional interface (discussed later in this article)
that has a single method,get()
, which returns a value of type T
.
T
can be any type, allowing us to specify the return type of the get
method when we create a Supplier
object,
instead of when we define the Supplier
interface.
This is useful because it allows us to pass functions as parameters to other functions,
which can be very powerful when you want to create more flexible and reusable code.
For example, to create an InitLoopCondAction
,
you need to pass a Condition
, aka a Supplier<Boolean>
that returns true
when the action needs to be repeated.
You might notice that in the examples in the Base Actions section,
we don't actually define a Condition
object when we create an InitLoopCondAction
,
we instead create a function that returns a Condition
object.
Lambda Functions
Lambda functions are a way to define functions without giving them a name, also known as anonymous functions. They are useful when you only need to use a function once, and don't want to define it elsewhere in your code.
For example, in the PIDFActionEx
class in the Base Actions section,
we define a function hasArrived
that returns true if the motor is within 50 encoder ticks of the target position.
The return type Condition
indicates that we are actually returning a function,
and not whether the motor has arrived or not at the time hasArrived
is called.
When defining hasArrived
, we use {}
to specify that we are defining a function to return,
and not returning the Boolean value of the expression inside the braces.
When creating the InitLoopCondAction
, we pass hasArrived
into the superclass constructor,
which is the constructor of the InitLoopCondAction
class.
Functional Interfaces
Functional interfaces are interfaces that have a single abstract method, which is why they are also known as Single Abstract Method (SAM) interfaces.
In Java, functional interfaces are used to define lambda functions, as the lambda function must match the signature of the single abstract method in the functional interface.
As mentioned before, Supplier<T>
is a functional interface with a single method, get()
.
This is why we can pass a lambda function that returns a Boolean
into the InitLoopCondAction
constructor,
as the lambda function matches the signature of the get
method in the Supplier
interface.
In Kotlin, functional interfaces are not explicitly defined, as Kotlin has first-class support for lambda functions. This means that you can pass a lambda function directly into a function that expects a functional interface, or a function that expects a lambda function.
However, to ensure compatibility with Java, Expressway uses Java's default functional interfaces,
such as Supplier
and Consumer
.
However, some parts of Expressway will either create a Kotlin functional interface,
or a typealias for a Java functional interface, to make the code more readable.
For example, Condition
is a typealias for Supplier<Boolean>
,
which allows us to not specify the type of the Supplier
when we create a Condition
object.
Higher Order Functions
Higher order functions are functions that take other functions as parameters, or return functions as results.
This is why we can pass a lambda function into the InitLoopCondAction
constructor,
as the InitLoopCondAction
constructor is a higher order function.
Higher order functions are useful when you want to create more flexible and reusable code.
Java does not have first-class support for higher order functions, which is why we need to use functional interfaces to define lambda functions.
Other Functional Interfaces
There are many other functional interfaces in Java, such as Function
, BiFunction
, Predicate
, and Consumer
.
The other two functional interfaces used in Expressway are BiFunction
and Consumer
.
BiFunction<T, U, R>
is a functional interface with a single method, apply(T t, U u) : R
,
that takes two parameters of type T
and U
, and returns a value of type R
.
It is the superclass of FeedforwardFun
, which is used in the PIDFController
class.
Consumer<T>
is a functional interface with a single method, accept(T t)
,
that takes a parameter of type T
, and does not return a value.
It used in the PIDToPoint class to allow the user to specify a function
that sets the powers of drivetrain motors based on the result of the PID controller.