Drive pipelines are an extensible method to create multiple different ways of driving a robot. Since pipelines are just lambdas, they are highly customizable.
Some "stock" classes (inputs, processors, and outputs) are available in the org.team1540.rooster.drive.pipeline
package.
A pipeline can be used for almost any concievable method of drivetrain control, including standard open-loop teleop drive, closed-loop motion profiling, and anywhere in between.
Pipelines consist of three different kinds of stages: inputs, processors, and outputs. Since inputs, processors, and outputs are just Suppliers
, Functions
, and Consumers
respectively, they can be extended easily and flexibly.
-
An input produces target values for processing; for example, an input could get current values from the driver's joysticks, or the currently executing point in a motion profile.
-
A processor, well, processes values: for example, a closed-loop processor might take a desired position, velocity, and/or acceleration and convert them into setpoints, feed-forwards, etc. to send to motors. Note that processors can receive data from things that are not the currently configured input; for example, a gyro.
-
An output turns values from a processor into commands for motors or other things. An output for Talon SRX motors might just pass a setpoint to the Talons' native closed-loop functionality, while an output for PWM motors might perform additional PID logic.
Control two talons in open-loop tank drive:
Executable pipeline = new SimpleJoystickInput(new Joystick(0), 1, 5, false, false)
.then(new CTREOutput(leftTalon, rightTalon));
Breakdown:
SimpleJoystickInput(new Joystick(0), 1, 5, false, false)
: Takes values from a joystick on port 0, with axis 1 as the left and axis 5 on the right, inverting neither.then(new CTREOutput(leftTalon, rightTalon))
: Sends the output of the previousSimpleJoystickInput
to yourleftTalon
andrightTalon
. Since the output ofSimpleJoystickInput
only sets the feed-forward (i.e. raw throttle) term, it'll automatically usePercentOutput
output mode.
Executable pipeline = new ProfileInput(leftProfile, rightProfile)
.then(new OpenLoopFeedForward(kV, vIntercept, kA))
.then(new CTREOutput(leftTalon, rightTalon));
Breakdown:
ProfileInput
takes values from two providedMotionProfile
instances and returns the setpoint for the current time. The timer starts when the pipeline is first executed.OpenLoopFeedForward
takes the velocity and acceleration setpoints from theProfileInput
and calculates a suitable feed-forward for them using coefficients you provide, Oblarg-style. It then passes those velocities down.CTREOutput
, since it's receiving position setpoints from theProfileInput
, tells the Talon closed-loop to PID to those setpoints while providing the feed-forward from theOpenLoopFeedForward
as an additional bump term.
A properly composed pipeline (i.e. with an input on one end and an output on the other) implements Executable
, so it can be used as the argument to a SimpleCommand
or SimpleLoopCommand
:
// drivePipeline contains your pipeline
Command command = new SimpleLoopCommand("Drive", drivePipeline, Robot.driveTrain);
Most "stock" pipeline elements pass around TankDriveData
instances to encapsulate position, velocity, etc. It's possible to define your own data classes but there's not too much reason to.
An input that returns the same TankDriveData
every time:
Executable pipeline = ((Input) () -> new TankDriveData().withVelocities(0, 0))
.then(new CTREOutput(leftTalon, rightTalon))
A processor that multiplies the received position by two:
Executable pipeline = new SimpleJoystickInput(new Joystick(0), 1, 5, false, false)
.then(data -> data.modifyPositions(
(left) -> left.isPresent() ? left.getAsDouble() * 2 : left,
(right) -> right.isPresent() ? right.getAsDouble() * 2 : right)
.then(new CTREOutput(leftTalon, rightTalon))
Here's an output that just prints the data it receives instead of sending it to a motor:
Executable pipeline = new SimpleJoystickInput(new Joystick(0), 1, 5, false, false)
.then(data -> System.out.println(data))