Creating your first Robot
The Robot class is the heart of your robot’s code. It serves as a centralized container
for all your hardware devices and subsystems (Attachments), providing a clean
structure and powerful features to simplify your code.
You should create a new Robot class for each type of physical robot you’ve built.
1. Create Your Robot Class
Section titled “1. Create Your Robot Class”First, create a new class that inherits from the abstract Robot class.
This class requires an FTC HardwareMap to be passed to its constructor.
import com.qualcomm.robotcore.hardware.HardwareMapimport dev.kingssack.volt.robot.Robot
class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) { // Your hardware and attachments will be defined here}import com.qualcomm.robotcore.hardware.HardwareMap;import dev.kingssack.volt.robot.Robot;
public class MyRobot extends Robot { // Your hardware and attachments will be defined here
public MyRobot(HardwareMap hardwareMap) { super(hardwareMap); }}2. Defining Hardware
Section titled “2. Defining Hardware”Volt uses Kotlin’s property delegation to make hardware initialization clean and concise.
Instead of calling hardwareMap.get() for every device, you can use the helper functions provided by the Robot class.
To define a device, use the by keyword followed by the appropriate helper function,
passing the device name as configured in your robot’s hardware configuration.
Here are some of the available Hardware Property Delegates:
motor(name: String)forDcMotorservo(name: String)forServocrServo(name: String)forCRServoimu(name: String)forIMUhuskyLens(name: String)forHuskyLensdistanceSensor(name: String)forRev2mDistanceSensorcolorSensor(name: String)forNormalizedColorSensoranalogInput(name: String)forAnalogInput
Let’s add a DcMotor and an IMU:
import com.qualcomm.robotcore.hardware.HardwareMapimport dev.kingssack.volt.robot.Robot
class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) { // Motors private val motor1 by motor("m1")
// Sensors private val imu by imu("imu")}Java does not support these helper methods, so it has to use hardwareMap.get().
import com.qualcomm.robotcore.hardware.HardwareMap;import dev.kingssack.volt.robot.Robot;
public class MyRobot extends Robot { // Motors private final DcMotor motor1;
// Sensors private final IMU imu;
public MyRobot(HardwareMap hardwareMap) { super(hardwareMap); motor1 = hardwareMap.get(DcMotor.class, "m1"); imu = hardwareMap.get(IMU.class, "imu"); }}In Volt, subsystems like an intake mechanism, shooter,
or arm are called Attachments. The Robot class is designed to manage these attachments automatically.
To add Attachments, use the provided attachment builder function.
Let’s add an attachment to control our DcMotor:
class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) { private val motor1 by motor("m1")
private val imu by imu("imu")
// Attachments val exampleAttachment = attachment { DcMotorAttachment("Example", motor1, 0.5, 1000) }}public class MyRobot extends Robot { private final DcMotor motor1;
private final IMU imu;
// Attachments public final DcMotorAttachment exampleAttachment;
public MyRobot(HardwareMap hardwareMap) { super(hardwareMap); motor1 = hardwareMap.get(DcMotor.class, "m1"); imu = hardwareMap.get(IMU.class, "imu"); exampleAttachment = attachment(() -> new DcMotorAttachment( "Example", motor1, 0.5, 1000, 0, DcMotorSimple.Direction.FORWARD )); }}4. State
Section titled “4. State”The Robot class manages its state through a StateFlow of type RobotState.
This allows you to reactively observe the robot’s status from your OpModes. The possible states are:
Initializing: TheRobothas not finished initializing.Initialized: TheRobothas finished initializing, and all Attachments have been discovered.Idle: No Attachments are busy.Running: At least one Attachment reports that it is busy.Fault(val error: Throwable): An error has occurred.
5. The update() Method
Section titled “5. The update() Method”The update() method is called every tick while an OpMode is running.
The Robot class can also declare Actions using the VoltActionBuilder.
These can be complex sequences controlling your Actions or anything else.
For example let’s add a score sequence:
class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) { private val motor1 by motor("m1")
private val imu by imu("imu")
val exampleAttachment = attachment { DcMotorAttachment("Example", motor1, 0.5, 1000) }
// Actions fun score() = voltAction { +motor1.goTo(0.6, 200) +motor1.goTo(0.5, 0) }}public class MyRobot extends Robot { private final DcMotor motor1;
private final IMU imu;
public final DcMotorAttachment exampleAttachment;
public MyRobot(HardwareMap hardwareMap) { super(hardwareMap); motor1 = hardwareMap.get(DcMotor.class, "m1"); imu = hardwareMap.get(IMU.class, "imu"); exampleAttachment = attachment(() -> new DcMotorAttachment( "Example", motor1, 0.5, 1000, 0, DcMotorSimple.Direction.FORWARD )); }
// Actions public Action score() { return VoltActionBuilderKt.voltAction( this, builder -> { builder.unaryPlus(motor.goTo(0.6, 200)); builder.unaryPlus(motor.goTo(0.5, 0)); return Unit.INSTANCE; } ); }}Result
Section titled “Result”package org.firstinspires.ftc.teamcode.robot
import dev.kingssack.volt.attachment.DcMotorAttachmentimport dev.kingssack.volt.core.voltActionimport dev.kingssack.volt.robot.Robotimport com.qualcomm.robotcore.hardware.HardwareMap
class MyRobot(hardwareMap: HardwareMap) : Robot(hardwareMap) { private val motor1 by motor("m1") private val imu by imu("imu")
val exampleAttachment = attachment { DcMotorAttachment("Example", motor1, 0.5, 1000) }
fun score() = voltAction { +motor1.goTo(0.6, 200) +motor1.goTo(0.5, 0) }}package org.firstinspires.ftc.teamcode.robot;
import com.acmerobotics.roadrunner.Action;import com.qualcomm.robotcore.hardware.DcMotor;import com.qualcomm.robotcore.hardware.DcMotorSimple;import com.qualcomm.robotcore.hardware.HardwareMap;import dev.kingssack.volt.attachment.DcMotorAttachment;import dev.kingssack.volt.core.VoltActionBuilder;import dev.kingssack.volt.core.VoltActionBuilderKt;import dev.kingssack.volt.robot.Robot;import kotlin.Unit;
public class MyRobot extends Robot { private final DcMotor motor1; private final IMU imu;
public final DcMotorAttachment exampleAttachment;
public MyRobot(HardwareMap hardwareMap) { super(hardwareMap); motor1 = hardwareMap.get(DcMotor.class, "m1"); imu = hardwareMap.get(IMU.class, "imu"); exampleAttachment = attachment(() -> new DcMotorAttachment( "Example", motor1, 0.5, 1000, 0, DcMotorSimple.Direction.FORWARD )); }
public Action score() { return VoltActionBuilderKt.voltAction( this, builder -> { builder.unaryPlus(motor.goTo(0.6, 200)); builder.unaryPlus(motor.goTo(0.5, 0)); return Unit.INSTANCE; } ); }}Next Steps
Section titled “Next Steps”- Add Attachments to give your robot functionality
- Create an OpMode to control your robot
- Learn more about Actions
- Learn more about the VoltActionBuilder
- View all Hardware Property Delegates