Skip to content
Lucas Bubner edited this page Jun 2, 2025 · 77 revisions

In BunyipsLib, there are various utility classes that handle inputs and outputs. Thes features span from external features such as FtcDashboard, to items such as encoders and reading from input devices. This article generalises some of the most important operations related to I/O.

Input

Gamepad

Gamepad objects in BunyipsLib can be replaced with the more modern Controller class. This class provides customizability of bindings at the gamepad level, including setting your own unary functions for mapping, and predicates for button selection.

Important

gamepad1 and gamepad2 of BunyipsOpMode have been overridden to be Controller instances internally. No additional setup is required and this section will assume these gamepads are instances of Controller. For manual implementations, one will need to call the update() method periodically.

Tip

Controller provides shorthand aliases for gamepad inputs. See them in the JavaDoc.

Unary functions can be mapped to gamepad inputs; for instance, gamepads are initially mapped to the standard identity/linear function (x) -> x:

gamepad1.set(Controls.Analog.LEFT_STICK_Y, (x) -> x); // default behaviour

Important

Unrelated to the Controller, but do note the y-sticks, including left_stick_y, and right_stick_y, are inverted, meaning pushing them fully up will return -1 and fully down 1. This is an SDK thing which I haven't quite worked out why it exists.

Tip

There exists some built-in UnaryFunction instances you can use, including IDENTITY, SQUARE, SQUARE_KEEP_SIGN, CUBE, CUBE_KEEP_SIGN, and NEGATE.

The most common mapping is to use quadratic controls, such that $$f(x)=x^2\cdot \text{sgn}(x)$$:


This function is available as the built-in UnaryFunction.SQUARE_KEEP_SIGN instance.

To apply this function, it is passed into the set method with either an analog stick, as shown before, or you can use an AnalogGroup to define it for both sticks, both triggers, or all analog controls.

gamepad1.set(Controls.AnalogGroup.STICKS, UnaryFunction.SQUARE_KEEP_SIGN);
// function applied to all future gp1 left_stick_y, left_stick_x, right_stick_x, right_stick_y accesses

For buttons, this works similarly but instead uses a Predicate<Boolean> functional interface, for example:

gamepad2.set(Controls.A, (pressed) -> !pressed); // inverts gamepad2.a

You can also bind controls to other controls and even gamepads, for some reason. Might be useful for a system that switches around bindings depending on some condition.

gamepad1.set(Controls.X, (p) -> gamepad2.x); // not sure why you'd do this, but it's possible
gamepad1.set(Controls.Analog.LEFT_STICK_Y, (x) -> gamepad2.lsy);

Controller instances also have the getDebounced method, which will run rising-edge detection on a particular button. This detection initially ignores the first call to the method, which is a caveat that can be used in command-based TeleOp to make a trigger bind. Read the accompanying JavaDoc for more info.

// e.g.
@Override
protected void activeLoop() {
    if (gamepad1.a) {
        // executes every loop that A is held
    }
    if (gamepad1.getDebounced(Controls.A)) {
        // only executes once per press
    }
}

Encoders

There exists two Encoder classes that you might use throughout BunyipsLib for encoder operations. Do note that normally, you won't have to interface or instantiate these encoder classes yourself, as the Motor class internally uses an Encoder and other use cases rely on the built-in encoder interface via DcMotorEx.

Note

Unrelated to BunyipsLib, but high-resolution encoders, such as odometry pods, should be attached to ports 0 and 3, as Hubs only have two reliable quadrature encoder ports. Encoder counts will be missed for high resolution encoders on ports 1 and 2. You can read more about this here.

The Encoder class in BunyipsLib has several features, including:

  • Independent setting of encoder direction (without setting motor power direction)
  • Accumulation, meaning a "last known position" can be set and tracked from there
  • Extraction of acceleration information (with a built-in low-pass filter)

The other encoder class, offered by RoadRunner, the RawEncoder, is used for RoadRunner drive instances. It is not used elsewhere. More information can be found in the RoadRunner section.

Note

Also unrelated to BunyipsLib directly, but if velocity readings on an encoder exceed 32767 ticks/sec, they will overflow. The Encoder interfaces presented here have correction methods (RoadRunner does it internally by wrapping the RawEncoder you supply into an OverflowEncoder), and the standard BunyipsLib encoder has the useEncoderOverflowCorrection() method to enable correction.

IMU

The Inertial Measurement Unit is essential for gathering heading information from a robot. It can be accessed with the IMU interface, as per the SDK.

An additional hardware device extension exists for advanced IMU operations, called the IMUEx.

The IMUEx provides field-level readings for IMU readings, as well as setting the desired domain for yaw (either -180,180, 0,360, or 0,inf). Optionally supports multithreaded reads, but this can damage performance due to bus locks, so it is strongly not recommended. IMUEx also supports the BunyipsLib-obsolete LazyImu interface from RoadRunner.

Lazy initialisation can still be performed for an IMU via IMUEx. To allow lazy initialisation, replace your initialize method with lazyInitialize, which will delay initialisation until a getter is called.

// In a RobotConfig
hw.imu = getHardware("imu", IMUEx.class, d -> {
    d.lazyInitialize(...); // Same as initialize but will lazy-init

    d.setRefreshRate(Milliseconds.of(300)); // Extra IMUEx specific features!
});

IMUEx also allows for a "null IMU", available through the static IMUEx.none(), which will replicate an empty IMU for applications where an IMU is not required but still needed to be passed in.

For standard operations, the IMU interface from the SDK works perfectly well. For advanced operations such as lazy-init, refresh rate adjustments, and extended functionality, IMUEx is recommended. IMUEx implements IMU so it does not have any downsides.

Limit Switches

Limit switches are hardware devices that can be accessed through the TouchSensor class. It is defined like any other HardwareDevice and initialised like one.

Note

Unrelated to BunyipsLib, but REV Touch Sensors use the N+1th port when configuring the digital channels.

Sometimes, the isPressed() method on the TouchSensor will be inverted, so not pressing the switch will return true and vice versa. Internal implementations that use the TouchSensor assume that pressed is always true. You can combat this using an InvertibleTouchSensor. As the name implies, it will invert the readings of a TouchSensor and re-expose it with the same TouchSensor interface.

Tip

InvertibleTouchSensor can be grabbed in a RobotConfig the same as you would a normal TouchSensor via getHardware().

Servos

Servos in BunyipsLib can be controlled either with the stock Servo interface, or a ServoEx can be used.

Note: from BunyipsLib v5.1.0 to v6.1.0, ServoEx is known as the ProfiledServo.

A ServoEx is the same as the regular Servo interface, but adds these additional features:

  • Motion profiling, allowing you to control the velocity and acceleration of a servo
  • Position threshold for hardware optimisations
  • Refresh rate for additional minor hardware optimisations

An example of limiting a ServoEx instance to half speed (0.5 pos/sec, 1 pos/sec/sec) is shown, which internally uses a TrapezoidalProfile:

// Units are measured in the servo position as given to setPosition() usually,
// where 0 and 1 are left and right on the servo programmer
servoEx.setConstraints(new TrapezoidProfile.Constraints(0.5, 1.0));

// Future calls to setPosition will follow the motion profile

Caution

As ServoEx now uses a motion profile, it is important that setPosition is called periodically on every loop, otherwise the profile won't be able to update. BunyipsLib implementations that use servo instances already ensure that setPosition is executed periodically.

Optimising

In FTC, one of the most important aspects of making proper robot code is optimising loop times. A loop time is the time taken for a single iteration of the main loop in an OpMode. This time is crucial for ensuring that the robot can respond to inputs quickly and accurately, while also updating PID controllers and odometry systems in a timely manner.

Tip

Slow loop times are not usually caused by software implementations and libraries, but instead hardware reads and writes.

Loop times are shown automatically in the presence of MovingAverageTimer and DualTelemetry instances, such as in standard operation of a BunyipsOpMode. More information on the standard telemetry output is available in the Telemetry section below.

BunyipsLib takes care of many optimisations internally, including using manual bulk caching for motor reads as part of the BunyipsOpMode. This is the main optimisation to ensure loop times are as fast as possible.

BunyipsLib offers a few caching options that you can use to optimise your loop times further:

Motor

The Motor class, described in more detail in the Motor section, also has a few optimisations that can be used to speed up loop times. The two main ones are power caching and refresh rate.

Power caching is a feature that caches the last power set to the motor, and defines a tolerance around the power that will not update the motor if a newly commanded power is within this tolerance. The SDK already ignores values that are the exact same as the last call, but not those that are near the last call.

By caching, unnecessary writes to the motor controller are ignored, as requesting a power of 0.5001 when the motor is already at 0.5 is not going to impact your motor output.

Tip

Power caching is disabled by default in a Motor, enable it with a tolerance using setPowerDeltaThreshold(double). This value should realistically be around 0.005-0.02, depending on how precise you need your motor power to be. Also note that input powers of -1, 0, and 1 will ignore this threshold for safety.

You can also choose to set a refresh rate (minimum period between writes) for the motor. This optimisation is not as useful as power caching (as it will introduce lag), but can be used to ensure that the motor controller is not written to too frequently. The method for this is setPowerRefreshRate(Measure<Time>).

Note

For CRServos, you can use the SimpleRotator to get these optimisations (Motor extends SimpleRotator internally so you don't lose out on any optimisations - you can also choose to use SimpleRotator alone if you don't need the Motor features).

ServoEx

As exemplified in the section above, ServoEx also has some optimisations that can be used to speed up loop times. These are similar to the Motor optimisations, but are instead applied to servo positions.

It is enabled through the setPositionDeltaThreshold(double) method, which sets a tolerance around the last position set to the servo.

Like power refresh rate, refresh rate for position can also be applied to a ServoEx to ensure writes have a minimum period between them. This is accessed through the setPositionRefreshRate(Measure<Time>) method.

Note

Unrelated to BunyipsLib, servo ranges can be increased to their full extent as the robot Hub only enforces a PWM range from 600-2400 microseconds. It can be expanded to 500-2500 microseconds which can give your servo the full range it was designed for. You can do this by calling setPwmRange(new PwmRange(500, 2500)) on a ServoEx or ServoImplEx instance.

Other hardware

For USB devices, like cameras, processing is done on another thread, thus loop time is not affected by camera processing.

Note

Unrelated to BunyipsLib, the USB 2.0 port should never be used. This port shares the ground with the Wi-Fi chip on the hub, and static shock by this USB device will kill your robot connection.

Another optimisation is a library called Photon, which can be integrated by following the instructions on the Photon GitHub page. Photon paralellizes hardware reads and writes, and is developed by Eeshwar, alum from FTC 7244.

Caution

Photon is extremely buggy and not recommended for stable use. Photon may cause servos to not function while the library is active, and may cause motors to behave erratically. It is recommended to not use Photon in any official capacity.

Output

Robot Controller Lights

The Control and Expansion Hub have a singular Status LED attached to them. This light blinks in correspondence with the connection and voltage condition of the robot.

BunyipsLib hooks into these lights during the execution of BunyipsOpMode and other BunyipsLib-integrated OpModes, to provide safety warnings to others around and working with the robot. This adds functionality very similar to the FRC Robot Signal Light.

Note

The standard REV Status LED Blink Codes are listed here. Important blink codes, notably the low voltage one, override the custom blink patterns as defined in BunyipsLib.

Light Pattern Light Description When Status
standard green bluef blue Blue or green, flashing or solid Idle or in custom OpMode Standard Status LED Blink Codes are in effect. The robot is switched on.
orange Flashing orange Anytime The robot is on low voltage and the battery should be recharged. This is a standard Status LED Blink Code.
static_init Solid cyan BunyipsOpMode initialisation The robot is currently in static_init, initialising hardware and firing onInit(). This phase should not last long enough for it to be seen. The robot is able to issue hardware commands but is unlikely.
dynamic_init Flashing cyan BunyipsOpMode initialisation The robot is currently in dynamic_init, running initialisation loops such as waiting for a UserSelection or doing some other work such as vision. The robot may move during this phase to home actuators and servos.
ready Alternating green and cyan BunyipsOpMode initialisation The robot has completed initialisation and is ready waiting for the PLAY button to be pressed. Hardware loops have been inhibited to 5 Hz.
ready_error Solid yellow BunyipsOpMode initialisation The robot has completed initialisation and is waiting for the PLAY button to be pressed, but an exception was caught and handled during the initialisation routine. Check the Driver Station as this may be a gamepad zeroing fault (the DS will say "check gamepads") or programmer error.
running Fast flashing green BunyipsOpMode active loop The robot is currently running. Do not work on the robot while this pattern is displayed as all actuator command systems are live.
yellow Solid yellow BunyipsOpMode active loop DebugMode has been enabled by the programmer and has tripped from a pre-set condition. Robot functionality may be inhibited or limited.
finished Solid light gray/white BunyipsOpMode The robot has finished execution via finish(). Hardware calls are actively inhibited at 2 Hz during this phase and the OpMode is awaiting STOP by the Driver Station.
finished_nostop Slow flashing light gray/white BunyipsOpMode The robot has finished execution via finish() and is no-oping until STOP. Hardware calls are not being inhibited during this time as the parameter to inhibit hardware was disabled by the programmer.
estop Solid red BunyipsOpMode A critical uncaught exception has occurred where BunyipsOpMode has terminated execution. A stacktrace is available on the Driver Station and Logcat.
hwt Altn. green and light gray/white HardwareTester, RoadRunnerTuningOpMode Hardware Tester or RoadRunner tuning is active. Motors and actuators may move at any time at the operator's discretion, and interfering can impact tuning accuracy.

FtcDashboard

FtcDashboard is an external dependency used within BunyipsLib to accelerate development. It is essential in the operation of several systems, including RoadRunner tuning, live vision previews, field overlay, and live adjustment of variables.

Important

FtcDashboard can be accessed on the URL http://192.168.43.1:8080/dash for a Control Hub while connected to the robot.


Configuration variables are special fields that the dashboard client can seamlessly modify while the app is running. To mark a field as a config variable, declare it `static` and not `final` and annotate the enclosing class with `@Config`.
@Config
public class RobotConstants {
    public static int MAGIC_NUMBER = 32;
    public static PIDCoefficients TURNING_PID = new PIDCoefficients();
    // other constants
}

It’s conventional to name variables in uppercase and treat them as constants inside the code. While saved dashboard changes instantly apply to the code fields, code-side changes only propagate to the client on explicit refresh.

Also, keep the copy semantics of Java primitives in mind when using this feature. Why does the following OpMode fail to observe position offset changes during operation?

public class ServoArm {
    private Servo servo;
    private double posOffset;

    public ServoArm(HardwareMap hardwareMap, double posOffset) {
        this.servo = hardwareMap.get(Servo.class, "servo");
        this.posOffset = posOffset;
    }

    public void setPosition(double pos) {
        servo.setPosition(posOffset + pos);
    }
}

@TeleOp
@Config
public class StaleServoOpMode extends LinearOpMode {
    public static double SERVO_POS_OFFSET = 0.27;

    @Override
    public void runOpMode() {
        ServoArm arm = new ServoArm(hardwareMap, SERVO_POS_OFFSET);

        waitForStart();

        while (opModeIsActive()) {
            arm.setPosition(-gamepad1.left_stick_y);
        }
    }
}

The value of SERVO_POS_OFFSET is read once at the start of the OpMode to pass to the ServoArm constructor. The field posOffset gets an independent copy of SERVO_POS_OFFSET; it only gets the new SERVO_POS_OFFSET when the OpMode is reinitialised.

With some slight adjustments, position offset modifications can appear truly live,

@Config
public class ServoArm {
    public static double POS_OFFSET = 0.27;

    private Servo servo;

    public ServoArm(HardwareMap hardwareMap) {
        this.servo = hardwareMap.get(Servo.class, "servo");
    }

    public void setPosition(double pos) {
        servo.setPosition(POS_OFFSET + pos);
    }
}

public class FixedServoOpMode extends LinearOpMode {
    @Override
    public void runOpMode() {
        ServoArm arm = new ServoArm(hardwareMap);

        waitForStart();

        while (opModeIsActive()) {
            arm.setPosition(-gamepad1.left_stick_y);
        }
    }
}

FtcDashboard also supports gamepad input, however, the binding system can be axially incorrect and using a modified version of the client will be required. The wiki does not cover this process.

A live camera preview is possible by calling .startPreview() on a Vision instance, which will start a new SwitchableVisionSender.

Caution

FtcDashboard is not legal for use during official matches as per rule R706 (as of CM 2024 V6). It is otherwise permitted for use in the pits, or in any workshop environment. You can disable the dashboard from accepting connections by running the Enable/Disable Dashboard OpMode in the TeleOp list.

Telemetry

By default, telemetry is broadcasted from user code to the Driver Station. For many applications, this is perfectly fine behaviour; however, attempting to get this telemetry to also display on FtcDashboard, often for tests without a Driver Station, requires extra code.

DualTelemetry is a class that properly fuses FtcDashboard and Driver Station telemetry, unlike the built-in MultipleTelemetry alternative which is half-baked.

Tip

From contexts where access to DualTelemetry is ambiguous, such as in a subsystem, you can use the static utilities smartLog and smartAdd to add logs or telemetry to both the Driver Station and Dashboard. Using a DualTelemetry instance is not necessary to use these utilities.

DualTelemetry also comes with several features including integrated functional CSS styling for depth in messages, and the ability to use telemetry as a normal object while having smart parsing for FtcDashboard. It is expected that through the use of DualTelemetry, all Driver Station telemetry is also shown on the dashboard.

Tip

BunyipsOpMode instances override the telemetry field under the hood to supply a DualTelemetry instance. No additional setup is required to use this class, since DualTelemetry extends the Telemetry interface.

Using methods on DualTelemetry is the same as it would be for normal telemetry, exposing one additional method, add(). This method works similarly to addLine() and addData(), but removes the need to input a tag as used in addData(). The add() method returns an HtmlItem instance, which can use a builder-like pattern to apply CSS styles. (e.g. telemetry.add("hi!").bold();)

Important

All format strings in DualTelemetry (and across BunyipsLib) uses the Text utility for string formatting. Review it in the Utilities section.

DualTelemetry also prettifies telemetry, providing you with status bars for elapsed time, loop time, gamepad input, and OpMode state. No additional setup is needed to use these features on a BunyipsOpMode.

A figure is provided labelling the standard output of a BunyipsOpMode with no extra telemetry calls.

Warning

Some features on DualTelemetry, such as addLine() and accessing .log().add() are no longer supported. They will raise deprecation warnings (the method list here is not exhaustive). Instead, use the alternative as listed by the JavaDoc (such as using add() or .log(message)).

The System Controller

Many applications throughout FTC require the usage of system controllers to correct for error. BunyipsLib provides an interface, called the SystemController, that represents any type of open-loop or closed-loop control. This interface is passed into several of the built-in functions and tasks of BunyipsLib, especially those which perform correction on measured error.

You can review the API documentation of this interface here.

The main implementations of this interface are PID (feedback), and various feedforward controllers.

Tip

System controllers can be tuned dynamically easily with the help of the setCoefficients method! Simply call it in an active loop environment to update your controllers with static variables (class annotated with @Config), and you can tune your PID in real time on FtcDashboard.

PID (Proportional-Integral-Derivative) controllers

The main feedback controller is the PID(F) controller. The PID controller is the most well-known controller in control theory, allowing errors in a system to be corrected. The F in the PIDF controller is an additional parameter similar to a static friction gain (kS), as described in the feedforward sections. It is not usually considered a feedback element as it is technically a feedforward element.

Tip

To learn more about the PID controller, have a look at this Game Manual 0 page.

The equation used for a PIDF controller is: $$f(t)=K_p\cdot e(t)+K_i\cdot \int_{0}^{t}e(\tau)d\tau+K_d\cdot\frac{d}{dt}e(t)+K_f \cdot s_p,\quad e(t)=s_p - p_v$$, where $s_p$ is the setpoint, or target value, and $p_v$ is the process value, or current state of the system.

Tuning PID

The most important part of any system controller is the tuning process. In order to dynamically set the coefficients of any SystemController, the setCoefficients method will help.

setCoefficients is a generic method that takes in a number of double arguments, with the specification of how many arguments being defined by the controller itself at runtime.

A common pattern is to have PID coefficients update based on inputs from FtcDashboard, live from any BunyipsOpMode via the RobotConfig:

@Config // for FtcDashboard tuning kP kI kD
public class Robot extends RobotConfig {
    public static double kP = 1, kI = 0, kD = 0.001; // example coefficients

    @Override
    protected void onRuntime() {
        motor = getHardware("motor", Motor.class, (d) -> {
            // any standard motor setup...

            PIDController pid = new PIDController(kP, kI, kD);
            d.setRunToPositionController(pid);

            BunyipsOpMode.ifRunning(o -> o.onActiveLoop(() -> {
                // important line below! will update the PID coefficients dynamically on the execution of any BOM.
                //     Do note if using a composite controller (as described later),
                //     the coefficients will be the combination of all internal coefficients
                pid.setCoefficients(kP, kI, kD, 0.0);

                // also recommended for tuning PID, which will telemetry out the current and target positions for this motor.
                //     you can graph these values on FtcDashboard for optimal tuning, as you will need to fit the current position line
                //     to closely follow the target position line to achieve the best results.
                Motor.debug(d, "motor", o.telemetry);
            }));
        });
    }
}

Caution

You may have noticed an extra 0.0 parameter on the setCoefficients call. This is because PIDController (and variants PDController and PController) are just instances of PIDFController, so the setCoefficients call will expect four parameters (for P, I, D, F).

With an above configuration, or similar with your own loop or reference to the controllers, you are ready to tune PID. You should make a tuning (or even a No-op) OpMode to assist in tuning. Following the advice of logging "target vs. current position" is also recommended via Motor.debug.

Important

System controller tuning is a delicate process. Be careful and don't sporadically set your coefficients unreasonably high just because things are not moving. You probably messed up 10 minutes ago.

General tips for PID include:

  • System not responding enough? Increase kP.
  • System oscillates too much but kP can't be adjusted? Increase kD by a very small factor, avoiding rattling oscillations.
  • Use kI in moderation, a sufficiently tuned PDController will operate better than a PIDController with kI tuned due to integral windup
  • System acts weirdly around certain setpoints? Add a feedforward (using a feedforward controller below, or use kF for a gain based on the setpoint)

Caution

Too high of a kD can cause severe rattling oscillations (triangle waves) since the system response rate is not fast enough to account for the system dynamics.

Note that loop times do affect PID, if you are having strange differences in PID performance, tune in an OpMode that has similar loop times to the one you plan to use the PID in (BunyipsOpMode.setLoopSpeed() is one way for slowing down tuning OpModes).

The PIDFController class also has some additional features that can be customised, along with composition into a CompositeController to add feedforward components (explained in Feedforward controllers below).

Maximum Integrator Value

Note

Integrators introduce instability and hysteresis into feedback loop systems. It is strongly recommended that you avoid using integral gain unless absolutely no other solution will do - very often, problems that can be solved with an integrator can be better solved through use of a more-accurate feedforward.

A typical problem encountered when using integral feedback is excessive “wind-up” causing the system to wildly overshoot the setpoint. This can be alleviated in a number of ways - the PIDFController class enforces an integrator range limiter to help overcome this issue.

By default, the total output contribution from the integral gain is limited to be between -1.0 and 1.0.

The range limits may be increased or decreased using the setIntegrationBounds() method. There also exists the setClearIntegralOnNewSetpoint() method, which will reset integration back to 0 whenever a new setpoint is provided.

Integration Zone

Another way integral “wind-up” can be alleviated is by limiting the error range where integral gain is active. This can be achieved by setting the integration zone. If the error is more than the integration zone, the total accumulated error is reset, disabling integral gain. When the error is equal to or less than the integration zone, integral gain is enabled.

By default, the integration zone is disabled.

The integration zone may be set using the setIntegrationZone() method. To disable it, set it to Double.POSITIVE_INFINITY.

Continuous Input

Warning

If your mechanism is not capable of fully continuous rotational motion (e.g. a turret without a slip ring, whose wires twist as it rotates), do not enable continuous input unless you have implemented an additional safety feature to prevent the mechanism from moving past its limit!

Some process variables (such as the angle of a turret) are measured on a circular scale, rather than a linear one - that is, each “end” of the process variable range corresponds to the same point in reality (e.g. 360 degrees and 0 degrees). In such a configuration, there are two possible values for any given error, corresponding to which way around the circle the error is measured. It is usually best to use the smaller of these errors.

To configure a PIDFController to automatically do this, use the enableContinuousInput() method.

Derivative Smoothing

Increasing the derivative term of a PIDFController can cause severe oscillations.

This is because the nature of the derivative when it attempts to slow down the rate of change of the system can create an unstable feedback loop resulting in oscillations that increase in amplitude. The same thing can happen when our source of data is unreliable and noisy. While we cannot perfectly fix noisy data without a perfect model we can use a series of filters to remove much of the high-frequency noise that appears in our measurements.

A low-pass filter is used internally to smooth out the derivative of error. This helps reduce oscillations based on one gain, the low-pass gain.

This gain must be within the range (0, 1) exclusive, and by default is 0.8 to smoothen out all PIDs. By increasing this value, the derivative is smoothed further, responding to less change and generating a smoother curve. Gains around to 0.8-0.9 provide a decent smoothing, and can be reduced if needed if a faster reaction time is desired.


You can adjust the used low-pass filter gain via the setDerivativeSmoothingGain() method.

Output Clamping

The output of a PIDFController can be clamped via the setOutputClamps() method - this ensures your output never responds with a value greater in magnitude than the specified domain.

Feedforward controllers

While PID is a feedback controller, feedforward controllers take known kinematic properties of a system and assist the system's output to rely less on pure feedback. This can reduce oscillation as an error can be corrected before the error is created. In BunyipsLib, there are three feedforward controllers ported from WPILib that can be used. Each of these controllers have sets of new coefficients that can be tuned to model your system kinematically.

Feedforward is added to the end of your feedback output controller, such that output = pid + ff. A CompositeController will assist in the merging process of feedback and feedforward.

Tip

Be sure to use the same process as your feedback controllers using FtcDashboard to tune quickly! The composing controllers section below will elaborate on how setCoefficients calls work with multiple controllers.

Simple permanent-magnet DC motor feedforward.

The SimpleMotorFeedforward is used for any simple motor with static friction, velocity, and acceleration gains. The equation used for SimpleMotorFeedforward is: $$f(t)=K_s \cdot \text{sgn}(v(t)) + K_v \cdot v(t) + K_a \cdot a(t)$$

SimpleMotorFeedforward smf = new SimpleMotorFeedforward(
        0.0, // kS
        0.0, // kV
        0.0, // kA
        () -> motorClassMotor.getVelocity(), // v(t) velocity supplier
        () -> motorClassMotor.getAcceleration() // a(t) acceleration supplier - assumes you're using a Motor instance
);

Note that if you're not using kV or kA, you don't need to supply velocity or acceleration information (returning () -> 0 will work).

Tip

If possible, use an ElevatorFeedforward or ArmFeedforward to model your system! This feedforward is a general feedforward used if there are no better kinematic models. The other two feedforward controllers also have SimpleMotorFeedforward components, so nothing is lost.

Elevator feedforward modelled as a lift constantly acting against the force of gravity.

The ElevatorFeedforward is the same as the SimpleMotorFeedforward but includes an extra gain for the constant force of gravity. The equation used is: $$f(t)=K_s \cdot \text{sgn}(v(t)) + K_v \cdot v(t) + K_a \cdot a(t) + K_g$$

Tip

To tune kG, set all of your other coefficients to zero, then increase kG until the arm can hold itself relatively in place (to zero out against the force of gravity).

ElevatorFeedforward ef = new ElevatorFeedforward(
        0.0, // kS
        0.0, // kG
        0.0, // kV
        0.0, // kA
        () -> motorClassMotor.getVelocity(), // v(t) velocity supplier
        () -> motorClassMotor.getAcceleration() // a(t) acceleration supplier
);

As with SimpleMotorFeedforward, the velocity and acceleration suppliers can be set to zero if you don't plan on using kV or kA.

Rotating arm modelled as a motor acting against the force of gravity on a beam suspended at an angle.

The ArmFeedforward is an essential feedforward for rotating arms that may experience asymmetric weight balance if used with pure feedback control. The Arm feedforward uses a cosine to the angle of the arm, effectively gain scheduling more correction at the endpoints and zeroing the extra correction when the arm is vertical. The equation used for an ArmFeedforward is: $$f(t)=K_s \cdot \text{sgn}(v(t)) + K_v \cdot v(t) + K_a \cdot a(t) + K_{\text{cos}} \cdot \cos(s(t))$$

Note

This feedforward is the only one that requires the use of the BunyipsLib unit system! In the example provided below, an EncoderTicks.Generator will be used to convert encoder ticks into angles. Review the docs for EncoderTicks.Generator for more configuration options, such as adding a gear reduction.

EncoderTicks.Generator angleGenerator = EncoderTicks.createGenerator(motor);
ArmFeedforward af = new ArmFeedforward(
        0.0, // kS
        0.0, // kCos
        0.0, // kV
        0.0, // kA
        angleGenerator::getAngle,
        angleGenerator::getAngularVelocity,
        angleGenerator::getAngularAcceleration
);

Tip

To tune kCos, set all other coefficients to zero and increase kCos slowly at an endpoint until the arm can hold itself relatively in place. Ensure that it is able to hold itself in place for all angles it can be suspended from.

As with SimpleMotorFeedforward, the angular velocity and acceleration suppliers can be set to zero (returning DegreesPerSecond.zero() and DegreesPerSecondPerSecond.zero()) if you don't plan on using kV or kA.

Composing Feedforward with Feedback

The CompositeController can be used to compose different SystemController instances. This new controller is in itself a SystemController instance, allowing you to pass it to the Motor class or wherever else as a singular instance. To compose, you can use the .compose() method on an existing SystemController, or use the standard constructor for CompositeController:

PIDController pid = new PIDController(/* ... */);
SimpleMotorFeedforward ff = new SimpleMotorFeedforward(/* ... */);
CompositeController c = pid.compose(ff, (a, b) -> a + b); // second arguments dictates
                                                          // how these controllers should be composed.
                                                          // usually you want to just add them so you
                                                          // can use this BiFunction here (or Double::sum)

motor.setRunToPositionController(c); // use c as you usually would

// Note: when calling setCoefficients on this new controller, the coefficients are now determined as the
// union of coefficients, much as if you were to call setCoefficients on both controllers one after the other.
c.setCoefficients(kP, kI, kD, kF, kS, kV, kA); // pidf + simplemotorfeedforward

Note

Composing a PID controller with a feedforward controller will set the pidf() method of the SystemController to return the internal instance of the PID controller. Using two PIDs together is not supported and pidf() will throw an exception.

The Motor class

For effectively every application in FTC, you will be reaching for a motor object to interface with a motor connected to a port. By default, you will be utilising the DcMotor (and extension variant DcMotorEx). These motor interfaces come with four separate modes, as described in the official Javadoc.

Important

While the raw power mode is called RUN_WITHOUT_ENCODER, it does not imply the motor will run with encoders not tracking - it simply means it will not use encoders to regulate power output internally. Consult the table below for a description of each DcMotor.RunMode. Modes that use a SystemController will return true as being classified as a PID mode (via RunMode.isPIDMode()).

Mode Purpose
RUN_WITHOUT_ENCODER Runs the motor at whatever speed is achieved by applying a fraction (in [-1, 1]) of the available voltage to the motor.
RUN_USING_ENCODER Attempts to run the motor at the specified signed velocity, either through setVelocity or as a fraction of the maximum declared velocity of the motor in ticks per second through setPower. An encoder is required for this mode.
RUN_TO_POSITION Rotates the motor in whatever direction to cause the encoder reading to advance or retreat to the setTargetPosition position. An encoder is required for this mode.
STOP_AND_RESET_ENCODER Transient mode that resets the encoder reading back to 0 and removes power temporarily. Note that standard encoder readings persist until the robot is power cycled. Note for the Motor, the Motor.resetEncoder() method is internally called.

In subsystems such as the HoldableActuator, the RUN_TO_POSITION mode is used to run a motor from its current position to a target position. The DcMotor class regulates the default implementation of RUN_TO_POSITION. However, this run mode has a few major limiting factors.

  1. Limited update cycle locked at 20Hz

While the RUN_TO_POSITION PID controller is run at the firmware level, not affecting the main loop times, it is - for some reason - hard locked at a 20Hz update cycle. This is very slow for a PID controller, and can cause unexpected behaviours due to too slow of a polling time. This video describes how polling interval affects the output of a PID controller.

  1. Coefficients are limited

Since the controller is built into the hub, the coefficients for it can be changed but custom terms such as kG, kF, etc cannot be added to the system on the controller level. This means all you have for a RUN_TO_POSITION is a kP term that sets a velocity gain, which is very slow and hard to work with.

Solution: The Motor

Without having to rewrite the internal code structures using RUN_TO_POSITION, BunyipsLib provides a drop-in replacement for the DcMotor. It leverages the same API surface as the DcMotor to provide SystemController access, as shown in the previous section.

Simply pass through a system controller using the methods setRunToPositionController or setRunUsingEncoderController for either mode (one is for the RUN_TO_POSITION positional tracking, one is for velocity tracking RUN_USING_ENCODERS), and calls to setPower will update these controllers.

Note

Since Motor is not bound by the locked 20Hz update loop, and instead your OpMode loop time, update cycles can easily be tripled! Blazing!

Using a RobotConfig allows an extremely simple way of getting a Motor instance up and running.

// You can access Motor directly as if you were to get a DcMotor!
protected void onRuntime() {
    hw.motor = getHardware(Motor.class, "motor", d -> {
        // perform initialisation as normal, while setting your system controllers!
        // do note an exception will be thrown if you try to use a system controller on a Motor that has not been set.
    });
}

Caution

In order to update the internal system controllers, it is important that setPower is called periodically on every loop. BunyipsLib implementations that use motor instances already ensure that setPower is executed periodically.

Motor also supports several loop time optimisation techniques, including power caching, refresh rate, and other utilities such as power rescaling, voltage compensation, and gain scheduling using an interpolated lookup table. Read the API docs for more information on these methods.

Note

Motor works by taking the desired mode and otherwise ignoring it on the actual motor, the underlying object of the actual motor on the firmware is always running in RUN_WITHOUT_ENCODER mode, allowing maximum speed control by your control algorithm.

Clone this wiki locally