Configurables

Configurables are runtime-modifiable variables that make testing, tuning, and debugging robot behavior easier without needing to recompile or reupload your code. You can think of them as live sliders or inputs exposed to your Panels Dashboard.

The Configurables Widget also supports search functionality.

What is a Configurable?

A Configurable is a static (Java) or @JvmField (Kotlin) variable marked in a class annotated with @Configurable. These variables are exposed in the Panels UI and can be changed while the robot is running.

Useful for things like:

  • PID tuning
  • Autonomous positions and paths
  • Behavioral toggles (e.g., enabling/disabling subsystems)
  • Testing new constants on-the-fly

Annotating Classes with @Configurable

To make a class’s fields configurable:

@Configurable
public class RobotConstants {
    public static int MAGIC_NUMBER = 32;
}
java

In Kotlin:

@Configurable
object RobotConstants {
    @JvmField
    var magicNumber = 32
}
kotlin

Real Examples

You can define configurables in many ways. Let's explore the styles supported.

  1. Java Class
@Configurable
public class TestJavaClass {
    public static int testInt = 1;
    public static boolean testBoolean = false;
    public static String testString = "Hello";
}
java
  1. Kotlin Class
@Configurable
class TestKotlinClass {
    companion object {
        @JvmField
        var testDouble: Double = 1.0
    }
}
kotlin
  1. Kotlin Object
@Configurable
object TestKotlinObject {
    @JvmField
    var testFloat: Float = 1.0f
}
kotlin

Supported Types

All fields must be:

  • public static (Java)
  • @JvmField inside an object or companion object (Kotlin) And must be non-final.

You can use:

  • Primitive types: int, double, boolean, etc.
  • Enums
  • Strings
  • Arrays and Lists
  • Maps (read-only unless exposed via a custom dashboard)
  • Custom types (detected automatically)
  • Generic types (via @GenericValue)

Custom Types

Custom objects are detected automatically.

public class CustomType {
    public final int id;
    public final String name;
    
    public CustomType(int id, String name) {
        this.id = id;
        this.name = name;
    }
}
java

You can nest custom types, too:

public class NestedType {
    public final CustomType child;

    public NestedType(CustomType child) {
        this.child = child;
    }
}
kotlin

Generic Types with @GenericValue

If you have a generic wrapper class:

public class TParamClass<T> {
    public final T value;
    public TParamClass(T value) { this.value = value; }
}
java

Then mark the instance with its type:

@GenericValue(tParam = Integer.class)
public static TParamClass<Integer> testGeneric = new TParamClass<>(42);
java

Kotlin:

@GenericValue(Int::class)
@JvmField
var testTParamClass = TParamClass(1)
kotlin

Gotchas

Static-only

All configurable fields must be static or top-level @JvmFields. Instance fields won’t be tracked by the dashboard.

Changes are One-Way

Updates on the dashboard side reflect immediately in your robot code. But updates in code do not update the dashboard until a refresh is triggered. This means:

  • Editing a value in code does not update it live on the dashboard.
  • You can overwrite dashboard changes if your code re-initializes the value.

The Common Pitfall: Copy Semantics

In Kotlin and Java, when you assign an object to a new variable, you copy the reference to the object, not the object itself. This means both variables point to the same memory location. However, when dealing with primitives (like int, double, etc.) or immutable objects, the value is copied directly. This can lead to unexpected behavior if one variable is modified, as the other variable won't reflect the change.

Example: Implementing a configurable Claw System

Bad Example

package org.firstinspires.ftc.teamcode.examples.configurables.copysemantics.bad

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import com.qualcomm.robotcore.hardware.HardwareMap

class RobotClaw(hardwareMap: HardwareMap, private val clawOffset: Double) {
    private val clawServo = hardwareMap.servo.get("claw")

    fun setPosition(position: Double) {
        clawServo.position = clawOffset + position
    }
}

@Configurable
@TeleOp(name = "Bad Example TeleOp")
class BadExampleOpMode : OpMode() {
    companion object {
        @JvmField
        var offset = 0.2
    }

    private lateinit var robotClaw: RobotClaw
    override fun init() {
        robotClaw = RobotClaw(hardwareMap, offset)
    }

    override fun loop() {
        robotClaw.setPosition(-gamepad1.left_stick_y.toDouble());
    }
}
kt

Problem:

In this example, the offset variable is passed as a value to the RobotClaw constructor during initialization. Since Double is a primitive type, its value is copied into the RobotClaw object. If offset is changed later during the OpMode (e.g., via Panels interface), the RobotClaw instance will not reflect the updated value. This leads to inconsistent behavior because the RobotClaw continues to use the old offset value.

Solution 1: Use a Mutable Shared State

One way to solve this issue is to make the clawOffset a mutable shared state that can be updated dynamically. Instead of passing the value directly, we store it in a shared location (e.g., a companion object) and reference it within the RobotClaw.

+
+
+
+
+
-
-
-
-
-
package org.firstinspires.ftc.teamcode.examples.configurables.copysemantics.fixed

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import com.qualcomm.robotcore.hardware.HardwareMap

@Configurable 
class RobotClaw(hardwareMap: HardwareMap) {
    companion object {
        @JvmField
        var clawOffset = 0.2
    }

    private val clawServo = hardwareMap.servo.get("claw")

    fun setPosition(position: Double) {
        clawServo.position = clawOffset + position
    }
}

@Configurable 
@TeleOp(name = "Fixed Example TeleOp")
class FixedExampleOpMode : OpMode() {
    companion object {
    @JvmField
    var clawOffset = 0.2
    }

    private lateinit var robotClaw: RobotClaw
    override fun init() {
        robotClaw = RobotClaw(hardwareMap)
    }

    override fun loop() {
        robotClaw.setPosition(-gamepad1.left_stick_y.toDouble());
    }
}
kt

Solution 2: Use a Lambda Function

Another elegant solution is to pass a lambda function that retrieves the current value of offset. This ensures that the RobotClaw always queries the latest value of offset whenever it needs it.

-
+
-
+
-
+
package org.firstinspires.ftc.teamcode.examples.configurables.copysemantics.lambda

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import com.qualcomm.robotcore.hardware.HardwareMap

//class RobotClaw(hardwareMap: HardwareMap, private val clawOffset: Double) { 
class RobotClaw(hardwareMap: HardwareMap, private val clawOffset: () -> Double) { 
    private val clawServo = hardwareMap.servo.get("claw")

    fun setPosition(position: Double) {
        //clawServo.position = clawOffset + position 
        clawServo.position = clawOffset() + position 
    }
}

@Configurable
@TeleOp(name = "Fixed Example with Lambda TeleOp")
class BadExampleOpMode : OpMode() {
    companion object {
        @JvmField
        var offset = 0.2
    }

    private lateinit var robotClaw: RobotClaw
    override fun init() {
        //robotClaw = RobotClaw(hardwareMap, offset) 
        robotClaw = RobotClaw(hardwareMap, { offset }) 
    }

    override fun loop() {
        robotClaw.setPosition(-gamepad1.left_stick_y.toDouble());
    }
}
kt

Playground: Random Test Arrays

You can even test the limits with things like:

@JvmField
var testRandomArray = arrayOf(
    1,
    1.0,
    1.0f,
    "test!",
    true,
    CustomType(1, "test!"),
    NestedType(1, "test!", CustomType(2, "test2!")),
    UnknownType(1),
    arrayOf(
        1,
        2,
        3
    ),
    mapOf(
        "one" to 1,
        "two" to 2,
        "three" to 3
    )
)
kotlin

Note: only supported types will render correctly on the dashboard.

---

Best Practices

  • Group related config values into logical classes like DriveConstants, ArmConfig, etc.
  • Keep types simple. Avoid overengineering unless you need complex nested types.
  • Never assume a configurable is updated in code. Always access live values directly from their source.

Example Configurables Files

Kotlin Object

package org.firstinspires.ftc.teamcode.examples.configurables

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.bylazar.ftcontrol.panels.configurables.annotations.GenericValue

@Configurable
object TestKotlinObject {
    @JvmField
    var testInt: Int = 1

    @JvmField
    var testLong: Long = 1L

    @JvmField
    var testDouble: Double = 1.0

    @JvmField
    var testFloat: Float = 1.0f

    @JvmField
    var testString: String = "test!"

    @JvmField
    var testBoolean: Boolean = false

    enum class TestEnum {
        TEST1,
        TEST2,
        TEST3
    }

    @JvmField
    var testEnum: TestEnum = TestEnum.TEST1

    @JvmField
    var testArray: Array<Int> = arrayOf(1, 2, 3)

    @JvmField
    var testList: List<Int> = listOf(1, 2, 3)

    @JvmField
    var testMap: Map<String, Int> = mapOf("one" to 1, "two" to 2, "three" to 3)

    class CustomType(
        val testInt: Int,
        val testString: String
    )

    @JvmField
    var testCustomType: CustomType = CustomType(1, "test!")

    class NestedType(
        val testInt: Int,
        val testString: String,
        val testCustomType: CustomType
    )

    @JvmField
    var testNestedType: NestedType = NestedType(1, "test!", CustomType(2, "test2!"))

    class UnknownType(
        val testInt: Int,
    )

    @JvmField
    var testUnknownType: UnknownType = UnknownType(1)

    @JvmField
    var testRandomArray = arrayOf(
        1,
        1.0,
        1.0f,
        "test!",
        true,
        CustomType(1, "test!"),
        NestedType(1, "test!", CustomType(2, "test2!")),
        UnknownType(1),
        arrayOf(
            1,
            2,
            3
        ),
        mapOf(
            "one" to 1,
            "two" to 2,
            "three" to 3
        )
    )

    class TParamClass<T>(
        val test: T
    )

    @JvmField
    @field:GenericValue(Int::class)
    var testTParamClass = TParamClass(1)
}
kt

Kotlin Class

package org.firstinspires.ftc.teamcode.examples.configurables

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.bylazar.ftcontrol.panels.configurables.annotations.GenericValue

@Configurable
class TestKotlinClass {
    companion object {
        @JvmField
        var testInt: Int = 1

        @JvmField
        var testLong: Long = 1L

        @JvmField
        var testDouble: Double = 1.0

        @JvmField
        var testFloat: Float = 1.0f

        @JvmField
        var testString: String = "test!"

        @JvmField
        var testBoolean: Boolean = false

        enum class TestEnum {
            TEST1,
            TEST2,
            TEST3
        }

        @JvmField
        var testEnum: TestEnum = TestEnum.TEST1

        @JvmField
        var testArray: Array<Int> = arrayOf(1, 2, 3)

        @JvmField
        var testList: List<Int> = listOf(1, 2, 3)

        @JvmField
        var testMap: Map<String, Int> = mapOf("one" to 1, "two" to 2, "three" to 3)

        class CustomType(
            val testInt: Int,
            val testString: String
        )

        @JvmField
        var testCustomType: CustomType = CustomType(1, "test!")

        class NestedType(
            val testInt: Int,
            val testString: String,
            val testCustomType: CustomType
        )

        @JvmField
        var testNestedType: NestedType = NestedType(1, "test!", CustomType(2, "test2!"))

        class UnknownType(
            val testInt: Int,
        )

        @JvmField
        var testUnknownType: UnknownType = UnknownType(1)

        @JvmField
        var testRandomArray = arrayOf(
            1,
            1.0,
            1.0f,
            "test!",
            true,
            CustomType(1, "test!"),
            NestedType(1, "test!", CustomType(2, "test2!")),
            UnknownType(1),
            arrayOf(
                1,
                2,
                3
            ),
            mapOf(
                "one" to 1,
                "two" to 2,
                "three" to 3
            )
        )

        class TParamClass<T>(
            val test: T
        )

        @JvmField
        @field:GenericValue(Int::class)
        var testTParamClass = TParamClass(1)
    }
}
kt

Java Class

package org.firstinspires.ftc.teamcode.examples.configurables;

import java.util.List;
import java.util.Map;

import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable;
import com.bylazar.ftcontrol.panels.configurables.annotations.GenericValue;


@Configurable
public class TestJavaClass {
    public static int testInt = 1;
    public static long testLong = 1L;
    public static double testDouble = 1.0;
    public static float testFloat = 1.0f;
    public static String testString = "test!";
    public static boolean testBoolean = false;

    public enum TestEnum {
        TEST1,
        TEST2,
        TEST3
    }

    public static TestEnum testEnum = TestEnum.TEST1;
    public static int[] testArray = {1, 2, 3};
    public static List<Integer> testList = List.of(1, 2, 3);
    public static Map<String, Integer> testMap = Map.of("one", 1, "two", 2, "three", 3);

    public static class CustomType {
        public final int testInt;
        public final String testString;

        public CustomType(int testInt, String testString) {
            this.testInt = testInt;
            this.testString = testString;
        }

        public int getTestInt() {
            return testInt;
        }

        public String getTestString() {
            return testString;
        }
    }

    public static CustomType testCustomType = new CustomType(1, "test!");

    public static class NestedType {
        public final int testInt;
        public final String testString;
        public final CustomType testCustomType;

        public NestedType(int testInt, String testString, CustomType testCustomType) {
            this.testInt = testInt;
            this.testString = testString;
            this.testCustomType = testCustomType;
        }

        public int getTestInt() {
            return testInt;
        }

        public String getTestString() {
            return testString;
        }

        public CustomType getTestCustomType() {
            return testCustomType;
        }
    }

    public static NestedType testNestedType = new NestedType(1, "test!", new CustomType(2, "test2!"));

    public static class UnknownType {
        public final int testInt;

        public UnknownType(int testInt) {
            this.testInt = testInt;
        }

        public int getTestInt() {
            return testInt;
        }
    }

    public static UnknownType testUnknownType = new UnknownType(1);

    public static Object[] testRandomArray = new Object[]{
            1,
            1.0,
            1.0f,
            "test!",
            true,
            new CustomType(1, "test!"),
            new NestedType(1, "test!", new CustomType(2, "test2!")),
            new UnknownType(1),
            new int[]{1, 2, 3},
            Map.of("one", 1, "two", 2, "three", 3)
    };

    public static class TParamClass<T> {
        public final T test;

        public TParamClass(T test) {
            this.test = test;
        }

        public T getTest() {
            return test;
        }
    }

    @GenericValue(tParam = Integer.class)
    public static TParamClass<Integer> testTParamClass = new TParamClass<Integer>(1);
}
java

Showcase OpMode

package org.firstinspires.ftc.teamcode.examples.configurables

import com.bylazar.ftcontrol.panels.Panels
import com.bylazar.ftcontrol.panels.configurables.annotations.Configurable
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp

@Configurable
@TeleOp(name = "Test Configurables OpMode")
class TestOpMode: OpMode() {
    companion object{
        @JvmField
        var testInt: Int = 1
        @JvmField
        var testBoolean: Boolean = false
        @JvmField
        var testDouble: Double = 1.0

        enum class States{
            TEST1,
            TEST2,
            TEST3
        }

        @JvmField
        var testEnum: States = States.TEST1

        @JvmField
        var testArray: Array<Int> = arrayOf(1, 2, 3)

        class CustomType(
            @JvmField var testInt: Int,
            @JvmField var testString: String
        ){
            override fun toString(): String {
                return "CustomType($testInt, $testString)"
            }
        }

        @JvmField
        var testCustomType: CustomType = CustomType(1, "test!")
    }

    val panelsTelemetry = Panels.getTelemetry()

    override fun init() {
        panelsTelemetry.debug("Init was ran!")
        panelsTelemetry.update(telemetry)
    }

    override fun loop() {
        panelsTelemetry.debug("INT: $testInt")
        panelsTelemetry.debug("BOOLEAN: $testBoolean")
        panelsTelemetry.debug("DOUBLE: $testDouble")
        panelsTelemetry.debug("ENUM: $testEnum")
        panelsTelemetry.debug("ARRAY: ${testArray.contentToString()}")
        panelsTelemetry.debug("CUSTOM TYPE: $testCustomType")
        panelsTelemetry.update(telemetry)
    }
}
kt

A library by Lazar from 19234 ByteForce.