Skip to content

Creating your first Attachment

An Attachment represents a distinct subsystem of your Robots, such as an intake, a claw, or an arm. The Attachment base class provides a powerful structure for managing state, creating Actions, and displaying telemetry, all of which are automatically handled by the Robot class.

There should be one Attachment per physical attachment/subsystem your team has built. Ideally, it operates independently from your other subsystems.

First, create a new class that inherits Attachment. The Attachment constructor requires a name for the attachment, which is used as an identifier and for logging telemetry. This name should be unique for each Attachment you create.

This class will need to receive a reference to all the hardware it will control. Examples of other hardware include:

  • DcMotor
  • Servo
  • CRServo
  • And more

In this example, we’ll create an Attachment called “Claw” controlling a Servo called claw:

import com.qualcomm.robotcore.hardware.Servo
import dev.kingssack.volt.attachment.Attachment
class Claw(private val claw: Servo) : Attachment("Claw") {
// Attachment logic will go here
}

The Robot class automatically calls the update() method on every registered Attachment during each tick of your OpMode.

The base Attachment already implements update() to add telemetry about the Attachment’s state (Idle, Running, or Fault). If you need continuous logic or custom telemetry, you can override this method.

In this example, we’ll log the claw’s current position:

import com.qualcomm.robotcore.hardware.Servo
import dev.kingssack.volt.attachment.Attachment
import org.firstinspires.ftc.robotcore.external.Telemetry
class Claw(private val claw: Servo) : Attachment("Claw") {
context(telemetry: Telemetry)
override fun update() {
super.update()
telemetry.addData("Position", claw.position)
}
}

Every Attachment has a state, which is managed automatically when using Actions. The possible states are:

  • Idle: The Attachment is not executing an Action.
  • Running: The Attachment is executing an Action.
  • Fault(val error: Throwable): An error has occurred.

The Attachment class provides helper functions to check the current state:

  • isBusy(): Returns true if the state is Running.
  • isFaulted(): Returns true if the state is Fault.
  • requireReady(): Throws an exception if the attachment is not Idle. This is useful for preventing new commands from starting while one is already running.

The most powerful feature of an Attachment is the action builder, which simplifies the creation of stateful, multi-step tasks. This is perfect for commands like “open the claw,” “move the arm to a position,” or “run the intake for a number of seconds.”

The action builder creates an Action and automatically manages the attachment’s state (Running -> Idle/Fault), including robust error handling.

The builder has three main parts:

  • init: This block runs once when the action begins. Use it for setup tasks, like setting a motor’s target position of moving a servo.
  • loop This block runs until it returns true. The main logic of your Action goes here. Return false to continue the Action, or true to complete the Action.
  • cleanup: This block runs once after the loop finishes or if an error occurs. Use it to reset hardware to a safe state, like turning off a motor.

Let’s create open() and close() Actions for the Claw:

import com.acmerobotics.roadrunner.Action
import com.qualcomm.robotcore.hardware.Servo
import dev.kingssack.volt.attachment.Attachment
import org.firstinspires.ftc.robotcore.external.Telemetry
class Claw(private val claw: Servo) : Attachment("Claw") {
private val OPEN_POSITION = 0.8
private val CLOSED_POSITION = 0.3
fun open(): Action = action {
init {
requireReady() // Require attachment to be idle
}
loop {
claw.position = OPEN_POSITION
true // Return true because the action is complete
}
// No cleanup required
}
fun close(): Action = action {
init {
requireReady()
}
loop {
claw.position = CLOSED_POSITION
true
}
}
context(telemetry: Telemetry)
override fun update() {
super.update()
telemetry.addData("Position", claw.position)
}
}

In this example, when the Actions built by either open() or close() is executed, the attachment’s state to Running, execute the logic, and then set the state back to Idle upon completion.

Once your Attachment is defined, you can instantiate it in your Robot class. Using the attachment builder method, the Robot will store it and automatically handle the Attachment’s update() method.

class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) {
private val clawServo by servo("cs")
val claw = attachment { Claw(clawServo) }
}
package org.firstinspires.ftc.teamcode.attachment
import com.acmerobotics.roadrunner.Action
import com.qualcomm.robotcore.hardware.Servo
import dev.kingssack.volt.attachment.Attachment
import org.firstinspires.ftc.robotcore.external.Telemetry
class Claw(private val claw: Servo) : Attachment("Claw") {
private val OPEN_POSITION = 0.8
private val CLOSED_POSITION = 0.3
fun open(): Action = action {
init { requireReady() }
loop {
claw.position = OPEN_POSITION
true
}
}
fun close(): Action = action {
init { requireReady() }
loop {
claw.position = CLOSED_POSITION
true
}
}
context(telemetry: Telemetry)
override fun update() {
super.update()
telemetry.addData("Position", claw.position)
}
}